diff --git a/boards/x86/panther/Kconfig.defconfig b/boards/x86/panther/Kconfig.defconfig index 4e31fe3323741..d04e07639e87d 100644 --- a/boards/x86/panther/Kconfig.defconfig +++ b/boards/x86/panther/Kconfig.defconfig @@ -27,4 +27,47 @@ endif config BLUETOOTH_MONITOR_ON_DEV_NAME default UART_QMSI_1_NAME if BLUETOOTH_DEBUG_MONITOR +if WIFI_WINC1500 + +config SPI + def_bool y +config GPIO + def_bool y + +if GPIO_QMSI + +config WINC1500_GPIO_0_NAME + default GPIO_QMSI_0_NAME +config WINC1500_GPIO_1_NAME + default GPIO_QMSI_1_NAME + +endif # GPIO_QMSI + +if SPI_QMSI +config SPI_CS_GPIO + def_bool y +config SPI_1_CS_GPIO_PORT + default GPIO_QMSI_0_NAME +config SPI_1_CS_GPIO_PIN + default 11 +config WINC1500_GPIO_0_NAME + string + default GPIO_QMSI_0_NAME +config WINC1500_GPIO_1_NAME + string + default GPIO_QMSI_1_NAME +endif + +endif # WIFI_WINC1500 + + + +config LEDS_GPIO_NAME + string + default GPIO_QMSI_0_NAME + +config SPI_0 + def_bool n + + endif # BOARD_PANTHER diff --git a/boards/x86/panther/board.c b/boards/x86/panther/board.c index fba20b897a609..40243318588f4 100644 --- a/boards/x86/panther/board.c +++ b/boards/x86/panther/board.c @@ -27,3 +27,44 @@ static int uart_switch(struct device *port) SYS_INIT(uart_switch, POST_KERNEL, CONFIG_UART_CONSOLE_INIT_PRIORITY); #endif + +#if defined(CONFIG_WIFI_WINC1500) + +static struct device *winc1500_gpio_config[WINC1500_GPIO_IDX_LAST_ENTRY]; + +struct device **winc1500_configure_gpios(void) +{ + struct device *gpio; + const int flags_noint_out = GPIO_DIR_OUT; + + gpio = device_get_binding(CONFIG_WINC1500_GPIO_1_NAME); + + gpio_pin_configure(gpio, CONFIG_WINC1500_GPIO_RESET_N, flags_noint_out); + winc1500_gpio_config[WINC1500_GPIO_IDX_RESET_N] = gpio; + + gpio = device_get_binding(CONFIG_WINC1500_GPIO_0_NAME); + + gpio_pin_configure(gpio, CONFIG_WINC1500_GPIO_CHIP_EN, flags_noint_out); + winc1500_gpio_config[WINC1500_GPIO_IDX_CHIP_EN] = gpio; + + gpio_pin_configure(gpio, CONFIG_WINC1500_GPIO_WAKE, flags_noint_out); + winc1500_gpio_config[WINC1500_GPIO_IDX_WAKE] = gpio; + + return winc1500_gpio_config; +} + +void winc1500_configure_intgpios(void) +{ + struct device *gpio; + + const int flags_int_in = (GPIO_DIR_IN | GPIO_INT | + GPIO_INT_ACTIVE_LOW | GPIO_INT_DEBOUNCE | + GPIO_INT_EDGE); + + gpio = device_get_binding(CONFIG_WINC1500_GPIO_0_NAME); + + gpio_pin_configure(gpio, CONFIG_WINC1500_GPIO_IRQN, flags_int_in); + winc1500_gpio_config[WINC1500_GPIO_IDX_IRQN] = gpio; + +} +#endif /* CONFIG_WIFI_WINC1500 */ diff --git a/boards/x86/panther/board.h b/boards/x86/panther/board.h index 3b123eebeedd2..b40a914fec021 100644 --- a/boards/x86/panther/board.h +++ b/boards/x86/panther/board.h @@ -30,4 +30,32 @@ #define USB_VUSB_EN_GPIO 28 #endif + +#if defined(CONFIG_WIFI_WINC1500) + +/* GPIO numbers where the WINC1500 module is connected to */ +#define CONFIG_WINC1500_GPIO_CHIP_EN 6 /* AP_GPIO6_ADC6 EXTERNAL_PAD_6 Out */ +#define CONFIG_WINC1500_GPIO_WAKE 5 /* AP_GPIO5_ADC5 EXTERNAL_PAD_5 Out */ +#define CONFIG_WINC1500_GPIO_IRQN 4 /* AP_GPIO4_ADC4 EXTERNAL_PAD_4 In Irq */ +#define CONFIG_WINC1500_GPIO_RESET_N 0 /* AP_GPIO_AON0 AON_GPIO_PAD_0 Out */ + +enum winc1500_gpio_index { + /* If all the GPIOs can be served by same driver, then you + * can set the values to be the same. The first enum should + * always have a value of 0. + */ + WINC1500_GPIO_IDX_CHIP_EN = 0, + WINC1500_GPIO_IDX_WAKE = 0, + WINC1500_GPIO_IDX_IRQN = 0, + + WINC1500_GPIO_IDX_RESET_N = 1, + + WINC1500_GPIO_IDX_LAST_ENTRY +}; + +struct device **winc1500_configure_gpios(void); +void winc1500_configure_intgpios(void); + +#endif /* CONFIG_WIFI_WINC1500 */ + #endif /* __BOARD_H__ */ diff --git a/boards/x86/panther/pinmux.c b/boards/x86/panther/pinmux.c index 961f73220a15f..e3a4513f44ecd 100644 --- a/boards/x86/panther/pinmux.c +++ b/boards/x86/panther/pinmux.c @@ -113,7 +113,7 @@ static void _pinmux_defaults(u32_t base) PIN_CONFIG(mux_config, 9, PINMUX_FUNC_C); PIN_CONFIG(mux_config, 16, PINMUX_FUNC_C); PIN_CONFIG(mux_config, 17, PINMUX_FUNC_C); - PIN_CONFIG(mux_config, 33, PINMUX_FUNC_A); + PIN_CONFIG(mux_config, 33, PINMUX_FUNC_B); PIN_CONFIG(mux_config, 40, PINMUX_FUNC_B); PIN_CONFIG(mux_config, 41, PINMUX_FUNC_B); PIN_CONFIG(mux_config, 42, PINMUX_FUNC_B); diff --git a/drivers/Kconfig b/drivers/Kconfig index ece137d45ba36..e1c23f4eb0db6 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -74,4 +74,5 @@ source "drivers/crypto/Kconfig" source "drivers/display/Kconfig" +source "drivers/wifi/Kconfig" endmenu diff --git a/drivers/Makefile b/drivers/Makefile index 8fe8bbcfefee1..447105da3c762 100644 --- a/drivers/Makefile +++ b/drivers/Makefile @@ -31,3 +31,4 @@ obj-$(CONFIG_DMA) += dma/ obj-$(CONFIG_USB) += usb/ obj-$(CONFIG_CRYPTO) += crypto/ obj-y += crc/ +obj-$(CONFIG_WIFI) += wifi/ diff --git a/drivers/wifi/Kconfig b/drivers/wifi/Kconfig new file mode 100644 index 0000000000000..a59836fbc6a33 --- /dev/null +++ b/drivers/wifi/Kconfig @@ -0,0 +1,30 @@ +# Kconfig - drivers configuration options + +# +# Copyright (c) 2015 Intel Corporation +# +# SPDX-License-Identifier: Apache-2.0 +# + + + + +menuconfig WIFI + bool "add support for WIFI Drivers" + default n + +if WIFI + +config WIFI_INIT_PRIORITY + int "WiFi driver init priority" + depends on WIFI + default 80 + help + WiFi device driver initialization priority. + Do not mess with it unless you know what you are doing. + Note that the priority needs to be lower than the net stack + so that it can start before the networking sub-system. + +source "drivers/wifi/winc1500/Kconfig" + +endif # WIFI diff --git a/drivers/wifi/Makefile b/drivers/wifi/Makefile new file mode 100644 index 0000000000000..adb279030c9f9 --- /dev/null +++ b/drivers/wifi/Makefile @@ -0,0 +1 @@ +obj-$(CONFIG_WIFI_WINC1500) += winc1500/ diff --git a/drivers/wifi/winc1500/Kconfig b/drivers/wifi/winc1500/Kconfig new file mode 100644 index 0000000000000..788601e135839 --- /dev/null +++ b/drivers/wifi/winc1500/Kconfig @@ -0,0 +1,39 @@ +# Kconfig - Atmel WINC1500 BSP and BUS configuration options +# +# WINC1500 options +# + +menuconfig WIFI_WINC1500 + bool + prompt "WINC1500 driver HAL Configuration" + default n + depends on WIFI + +if WIFI_WINC1500 + +config WINC1500_SPI_DRV_NAME + string "SPI device where WINC1500 is connected" + depends on WIFI_WINC1500 + default "SPI_1" + help + Specify the device name of the SPI device to which WINC1500 is + connected. + +config WINC1500_SPI_SLAVE + int "SPI Slave Select where WINC1500 is connected" + depends on WIFI_WINC1500 + default 1 + help + Specify the slave select pin of the SPI to which WINC1500 is + connected. + +config WINC1500_SPI_FREQ + int "SPI frequency to use with WINC1500" + depends on WIFI_WINC1500 + default 4 + help + SPI frequency to use with WINC1500 + +# TODO GPIO + +endif # WIFI_WINC1500 diff --git a/drivers/wifi/winc1500/Makefile b/drivers/wifi/winc1500/Makefile new file mode 100644 index 0000000000000..3d7246cd9e098 --- /dev/null +++ b/drivers/wifi/winc1500/Makefile @@ -0,0 +1,7 @@ +ZEPHYRINCLUDE +=-I${srctree}/ext/drivers/atmel/winc1500 +ZEPHYRINCLUDE +=-I${srctree}/drivers/wifi/winc1500 + +obj-$(CONFIG_WIFI_WINC1500) += \ + bsp/source/nm_bsp.o \ + bus_wrapper/source/nm_bus_wrapper.o \ + winc1500.o diff --git a/drivers/wifi/winc1500/bsp/include/nm_bsp.h b/drivers/wifi/winc1500/bsp/include/nm_bsp.h new file mode 100644 index 0000000000000..35bda710a5e42 --- /dev/null +++ b/drivers/wifi/winc1500/bsp/include/nm_bsp.h @@ -0,0 +1,100 @@ +/** + * Copyright (c) 2017 IpTronix + * + * SPDX-License-Identifier: Apache-2.0 + */ +/** + * Initialization for BSP such as Reset and Chip Enable Pins for WINC, delays, register ISR, enable/disable IRQ for WINC, ...etc. You must use this function in the head of your application to + * enable WINC and Host Driver communicate each other. + */ + +#ifndef _NM_BSP_H_ +#define _NM_BSP_H_ + +#include + +#define NMI_API + +/*! + * @fn sint8 nm_bsp_init(void); + * @note Implementation of this function is host dependent. + * @warning Missing use will lead to unavailability of host communication.\n + * + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +s8_t nm_bsp_init(void); + +/*! + * De-initialization for BSP (Board Support Package) + * @fn sint8 nm_bsp_deinit(void); + * @pre Initialize \ref nm_bsp_init first + * @note Implementation of this function is host dependent. + * @warning Missing use may lead to unknown behavior in case of soft reset.\n + * @see nm_bsp_init + * @return The function returns 0 for successful operations and + * a negative value otherwise. + */ +s8_t nm_bsp_deinit(void); + +/*! + * Resetting NMC1500 SoC by setting CHIP_EN and RESET_N signals low, + * then after specific delay the function will put CHIP_EN high then + * RESET_N high, for the timing between signals please review the + * WINC data-sheet + * + * @fn void nm_bsp_reset(void); + * @param [in] None + * @pre Initialize \ref nm_bsp_init first + * @note Implementation of this function is host dependent and called by HIF layer. + * @see nm_bsp_init + * @return None + */ +void nm_bsp_reset(void); + +/*! + * Sleep in units of milliseconds.\n + * This function used by HIF Layer according to different situations. + * @fn void nm_bsp_sleep(uint32); + * @brief + * @param [in] u32TimeMsec + * Time unit in milliseconds + * @pre Initialize \ref nm_bsp_init first + * @warning Maximum value must nor exceed 4294967295 milliseconds + * which is equal to 4294967.295 seconds.\n + * @note Implementation of this function is host dependent. + * @see nm_bsp_init + * @return None + */ +void nm_bsp_sleep(u32_t time_msec); + +/*! + * Register ISR (Interrupt Service Routine) in the initialization + * of HIF (Host Interface) Layer. + * When the interrupt trigger the BSP layer should call the isr_fun + * function once inside the interrupt. + * @fn void nm_bsp_register_isr(tpfNmBspIsr); + * @param [in] tpfNmBspIsr pfIsr + * Pointer to ISR handler in HIF + * @warning Make sure that ISR for IRQ pin for WINC is disabled by + * default in your implementation. + * @note Implementation of this function is host dependent and + * called by HIF layer. + * @see tpfNmBspIsr + * @return None + */ +void nm_bsp_register_isr(void (*isr_fun)(void)); + +/*! + * Synchronous enable/disable interrupts function + * @fn void nm_bsp_interrupt_ctrl(uint8); + * @brief Enable/Disable interrupts + * @param [in] u8Enable + * '0' disable interrupts. '1' enable interrupts + * @see tpfNmBspIsr + * @note Implementation of this function is host dependent and + * called by HIF layer. + * @return None + */ +void nm_bsp_interrupt_ctrl(u8_t enable); + +#endif /*_NM_BSP_H_*/ diff --git a/drivers/wifi/winc1500/bsp/include/nm_bsp_internal.h b/drivers/wifi/winc1500/bsp/include/nm_bsp_internal.h new file mode 100644 index 0000000000000..43876f6b6f070 --- /dev/null +++ b/drivers/wifi/winc1500/bsp/include/nm_bsp_internal.h @@ -0,0 +1,72 @@ +/** + * + * \file + * + * \brief This module contains NMC1500 BSP APIs declarations. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +/**@defgroup BSPDefine Defines + * @ingroup nm_bsp + * @{ + */ +#ifndef _NM_BSP_INTERNAL_H_ +#define _NM_BSP_INTERNAL_H_ + + +#include +#include + +#include "conf_winc.h" + +#define NM_EDGE_INTERRUPT (1) + +#define NM_DEBUG CONF_WINC_DEBUG +#define NM_BSP_PRINTF CONF_WINC_PRINTF + +/** + * + */ +struct winc1500_device { + struct device **gpios; + struct gpio_callback gpio_cb; + + struct device *spi_dev; + int spi_slave; +}; + +extern struct winc1500_device winc1500; + +#endif /* _NM_BSP_INTERNAL_H_ */ diff --git a/drivers/wifi/winc1500/bsp/source/nm_bsp.c b/drivers/wifi/winc1500/bsp/source/nm_bsp.c new file mode 100644 index 0000000000000..3412d8ca311ca --- /dev/null +++ b/drivers/wifi/winc1500/bsp/source/nm_bsp.c @@ -0,0 +1,164 @@ +/** + * + * \file + * + * \brief This module contains SAMD21 BSP APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include +#include + +#include "bsp/include/nm_bsp.h" +#include "common/include/nm_common.h" +#include "conf_winc.h" + +/** + * + */ +struct winc1500_device winc1500; + +void (*isr_function)(void); + +static inline void chip_isr(struct device *port, + struct gpio_callback *cb, + uint32_t pins) +{ + if (isr_function) { + isr_function(); + } +} + +/* + * @fn nm_bsp_init + * @brief Initialize BSP + * @return 0 in case of success and -1 in case of failure + */ +s8_t nm_bsp_init(void) +{ + isr_function = NULL; + + /* Initialize chip IOs. */ + winc1500.gpios = winc1500_configure_gpios(); + + winc1500.spi_dev = device_get_binding(CONFIG_WINC1500_SPI_DRV_NAME); + if (!winc1500.spi_dev) { + return -1; + } + + /* Perform chip reset. */ + nm_bsp_reset(); + + return 0; +} + +/** + * @fn nm_bsp_deinit + * @brief De-iInitialize BSP + * @return 0 in case of success and -1 in case of failure + */ +s8_t nm_bsp_deinit(void) +{ + /* TODO */ + return 0; +} + +/** + * @fn nm_bsp_reset + * @brief Reset NMC1500 SoC by setting CHIP_EN and RESET_N signals low, + * CHIP_EN high then RESET_N high + */ +void nm_bsp_reset(void) +{ + gpio_pin_write(winc1500.gpios[WINC1500_GPIO_IDX_CHIP_EN], + CONFIG_WINC1500_GPIO_CHIP_EN, 0); + gpio_pin_write(winc1500.gpios[WINC1500_GPIO_IDX_RESET_N], + CONFIG_WINC1500_GPIO_RESET_N, 0); + nm_bsp_sleep(100); + gpio_pin_write(winc1500.gpios[WINC1500_GPIO_IDX_CHIP_EN], + CONFIG_WINC1500_GPIO_CHIP_EN, 1); + nm_bsp_sleep(10); + gpio_pin_write(winc1500.gpios[WINC1500_GPIO_IDX_RESET_N], + CONFIG_WINC1500_GPIO_RESET_N, 1); + nm_bsp_sleep(10); +} + +/* + * @fn nm_bsp_sleep + * @brief Sleep in units of mSec + * @param[IN] time_msec + * Time in milliseconds + */ +void nm_bsp_sleep(u32_t time_msec) +{ + k_busy_wait(time_msec * MSEC_PER_SEC); +} + +/* + * @fn nm_bsp_register_isr + * @brief Register interrupt service routine + * @param[IN] isr_fun + * Pointer to ISR handler + */ +void nm_bsp_register_isr(void (*isr_fun)(void)) +{ + + isr_function = isr_fun; + + gpio_init_callback(&winc1500.gpio_cb, + chip_isr, + BIT(CONFIG_WINC1500_GPIO_IRQN)); + + gpio_add_callback(winc1500.gpios[WINC1500_GPIO_IDX_IRQN], + &winc1500.gpio_cb); +} + +/* + * @fn nm_bsp_interrupt_ctrl + * @brief Enable/Disable interrupts + * @param[IN] enable + * '0' disable interrupts. '1' enable interrupts + */ +void nm_bsp_interrupt_ctrl(u8_t enable) +{ + if (enable) { + gpio_pin_enable_callback(winc1500.gpios[WINC1500_GPIO_IDX_IRQN], + CONFIG_WINC1500_GPIO_IRQN); + } else { + gpio_pin_disable_callback(winc1500.gpios[WINC1500_GPIO_IDX_IRQN], + CONFIG_WINC1500_GPIO_IRQN); + } +} diff --git a/drivers/wifi/winc1500/bus_wrapper/include/nm_bus_wrapper.h b/drivers/wifi/winc1500/bus_wrapper/include/nm_bus_wrapper.h new file mode 100644 index 0000000000000..ebfba4298830a --- /dev/null +++ b/drivers/wifi/winc1500/bus_wrapper/include/nm_bus_wrapper.h @@ -0,0 +1,152 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 bus wrapper APIs declarations. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NM_BUS_WRAPPER_H_ +#define _NM_BUS_WRAPPER_H_ + +/** + * BUS Type + */ +#define NM_BUS_TYPE_I2C ((u8_t)0) +#define NM_BUS_TYPE_SPI ((u8_t)1) +#define NM_BUS_TYPE_UART ((u8_t)2) +/** + * IOCTL commands + */ +#define NM_BUS_IOCTL_R ((u8_t)0) /*!< Read only ==> I2C/UART. Parameter:tstrNmI2cDefault/tstrNmUartDefault */ +#define NM_BUS_IOCTL_W ((u8_t)1) /*!< Write only ==> I2C/UART. Parameter type tstrNmI2cDefault/tstrNmUartDefault*/ +#define NM_BUS_IOCTL_W_SPECIAL ((u8_t)2) /*!< Write two buffers within the same transaction + (same start/stop conditions) ==> I2C only. Parameter:tstrNmI2cSpecial */ +#define NM_BUS_IOCTL_RW ((u8_t)3) /*!< Read/Write at the same time ==> SPI only. Parameter:tstrNmSpiRw */ + +#define NM_BUS_IOCTL_WR_RESTART ((u8_t)4) /*!< Write buffer then made restart condition then read ==> I2C only. parameter:tstrNmI2cSpecial */ +/** + * @struct mm_bus_capabilities + * @brief Structure holding bus capabilities information + * @sa NM_BUS_TYPE_I2C, NM_BUS_TYPE_SPI + */ +struct mm_bus_capabilities { + u16_t max_trx_size; /*!< Maximum transfer size. Must be >= 16 bytes*/ +}; + +/** + * @struct nm_i2c_default + * @brief Structure holding I2C default operation parameters + * @sa NM_BUS_IOCTL_R, NM_BUS_IOCTL_W + */ +struct nm_i2c_default { + u8_t slave_address; + u8_t *buffer; /*!< Operation buffer */ + u16_t size; /*!< Operation size */ +}; + +/** + * @struct nm_i2c_special + * @brief Structure holding I2C special operation parameters + * @sa NM_BUS_IOCTL_W_SPECIAL + */ +struct nm_i2c_special { + u8_t slave_address; + u8_t *buffer1; /*!< pointer to the 1st buffer */ + u8_t *buffer2; /*!< pointer to the 2nd buffer */ + u16_t size1; /*!< 1st buffer size */ + u16_t size2; /*!< 2nd buffer size */ +}; + +/** + * @struct nm_spi_rw + * @brief Structure holding SPI R/W parameters + * @sa NM_BUS_IOCTL_RW + */ +struct nm_spi_rw { + u8_t *in_buffer; /*!< pointer to input buffer. Can be set to null and in this case zeros should be sent at MOSI */ + u8_t *out_buffer; /*!< pointer to output buffer. Can be set to null and in this case data from MISO can be ignored */ + u16_t size; /*!< Transfere size */ +}; + + +/*!< Bus capabilities. This structure must be declared at platform specific bus wrapper */ +extern struct mm_bus_capabilities nm_bus_capabilities; + + +/** + * @fn nm_bus_init + * @brief Initialize the bus wrapper + * @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure + */ +s8_t nm_bus_init(void *); + +/** + * @fn nm_bus_ioctl + * @brief send/receive from the bus + * @param [in] u8Cmd + * IOCTL command for the operation + * @param [in] parameter + * Arbitrary parameter depending on IOCTL + * @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure + * @note For SPI only, it's important to be able to send/receive at the same time + */ +s8_t nm_bus_ioctl(u8_t cmd, void *parameter); + +/** + * @fn nm_bus_deinit + * @brief De-initialize the bus wrapper + * @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure + */ +s8_t nm_bus_deinit(void); + +/* + * @fn nm_bus_reinit + * @brief re-initialize the bus wrapper + * @param [in] void *config re-init configuration data + * @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure + */ +s8_t nm_bus_reinit(void *); +/* + * @fn nm_bus_get_chip_type + * @brief get chip type + * @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure + */ +#ifdef CONF_WINC_USE_UART +u8_t nm_bus_get_chip_type(void); +#endif + +#endif /*_NM_BUS_WRAPPER_H_*/ diff --git a/drivers/wifi/winc1500/bus_wrapper/source/nm_bus_wrapper.c b/drivers/wifi/winc1500/bus_wrapper/source/nm_bus_wrapper.c new file mode 100644 index 0000000000000..9a360bc667bb3 --- /dev/null +++ b/drivers/wifi/winc1500/bus_wrapper/source/nm_bus_wrapper.c @@ -0,0 +1,231 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 bus wrapper APIs implementation. + * + * Copyright (c) 2015 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include +#include + +#include +#include +#include +#include +#include + +#include "bsp/include/nm_bsp.h" +#include "common/include/nm_common.h" +#include "bus_wrapper/include/nm_bus_wrapper.h" +#include "conf_winc.h" + +#define NM_BUS_MAX_TRX_SZ 256 + + +struct mm_bus_capabilities nm_bus_capabilities = { + NM_BUS_MAX_TRX_SZ +}; + +#ifdef CONF_WINC_USE_I2C + +#define SLAVE_ADDRESS 0x60 + +/** Number of times to try to send packet if failed. */ +#define I2C_TIMEOUT 100 + +static s8_t nm_i2c_write(u8_t *b, u16_t sz) +{ + /* Not implemented */ +} + +static s8_t nm_i2c_read(u8_t *rb, u16_t sz) +{ + /* Not implemented */ +} + +static s8_t nm_i2c_write_special(u8_t *wb1, u16_t sz1, + u8_t *wb2, u16_t sz2) +{ + /* Not implemented */ +} +#endif + +#ifdef CONF_WINC_USE_SPI + +static s8_t spi_rw(u8_t *mosi, u8_t *miso, u16_t size) +{ + int ret; + + spi_slave_select(winc1500.spi_dev, winc1500.spi_slave); + + ret = spi_transceive(winc1500.spi_dev, + mosi, size, + miso, miso ? size : 0); + if (ret) { + SYS_LOG_ERR("spi_rw spi_transceive fail %d\n", ret); + return M2M_ERR_BUS_FAIL; + } + + return M2M_SUCCESS; +} + +#endif + +/* + * @fn nm_bus_init + * @brief Initialize the bus wrapper + * @return 0 in case of success and -1 in case of failure + */ +s8_t nm_bus_init(void *pvinit) +{ + s8_t result = 0; + +#ifdef CONF_WINC_USE_I2C + /* Not implemented */ +#elif defined CONF_WINC_USE_SPI + struct spi_config spi_config; + int ret; + + /* configure GPIOs */ + winc1500.gpios = winc1500_configure_gpios(); + + /* setup SPI device */ + winc1500.spi_dev = device_get_binding(CONFIG_WINC1500_SPI_DRV_NAME); + if (!winc1500.spi_dev) { + SYS_LOG_ERR("spi device binding\n"); + return -1; + } + + spi_config.config = SPI_WORD(8) | SPI_TRANSFER_MSB; + spi_config.max_sys_freq = CONFIG_WINC1500_SPI_FREQ; + ret = spi_configure(winc1500.spi_dev, &spi_config); + if (ret) { + SYS_LOG_ERR("spi_configure fail %d\n", ret); + return -1; + } + winc1500.spi_slave = CONFIG_WINC1500_SPI_SLAVE; + SYS_LOG_INF("spi_configure OK\n"); + + winc1500_configure_intgpios(); + + nm_bsp_reset(); + nm_bsp_sleep(1); + + nm_bsp_interrupt_ctrl(1); + + SYS_LOG_INF("nm_bus_init:NOTICE:DONE\n"); +#endif + return result; +} + +/* + * @fn nm_bus_ioctl + * @brief send/receive from the bus + * @param[IN] cmd + * IOCTL command for the operation + * @param[IN] parameter + * Arbitrary parameter depenging on IOCTL + * @return 0 in case of success and -1 in case of failure + * @note For SPI only, it's important to be able to + * send/receive at the same time + */ +s8_t nm_bus_ioctl(u8_t cmd, void *parameter) +{ + sint8 ret = 0; + + switch (cmd) { +#ifdef CONF_WINC_USE_I2C + case NM_BUS_IOCTL_R: { + struct nm_i2c_default *param = (struct nm_i2c_default *)parameter; + + ret = nm_i2c_read(param->buffer, param->size); + } + break; + case NM_BUS_IOCTL_W: { + struct nm_i2c_default *param = (struct nm_i2c_default *)parameter; + + ret = nm_i2c_write(param->buffer, param->size); + } + break; + case NM_BUS_IOCTL_W_SPECIAL: { + struct nm_i2c_special *param = (struct nm_i2c_special *)parameter; + + ret = nm_i2c_write_special(param->buffer1, param->size1, + param->buffer2, param->size2); + } + break; +#elif defined CONF_WINC_USE_SPI + case NM_BUS_IOCTL_RW: { + struct nm_spi_rw *param = (struct nm_spi_rw *)parameter; + + ret = spi_rw(param->in_buffer, param->out_buffer, param->size); + } + break; +#endif + default: + ret = -1; + M2M_ERR("nm_bus_ioctl:ERROR:invalide ioclt cmd\n"); + break; + } + + return ret; +} + +/* + * @fn nm_bus_deinit + * @brief De-initialize the bus wrapper + */ +s8_t nm_bus_deinit(void) +{ + return M2M_SUCCESS; +} + +/* + * @fn nm_bus_reinit + * @brief re-initialize the bus wrapper + * @param [in] void *config + * re-init configuration data + * @return 0 in case of success and -1 in case of failure + * @author Dina El Sissy + * @date 19 Sept 2012 + * @version 1.0 + */ +s8_t nm_bus_reinit(void *config) +{ + return 0; +} + diff --git a/drivers/wifi/winc1500/conf_winc.h b/drivers/wifi/winc1500/conf_winc.h new file mode 100644 index 0000000000000..afd1fece49de4 --- /dev/null +++ b/drivers/wifi/winc1500/conf_winc.h @@ -0,0 +1,103 @@ +/** + * + * \file + * + * \brief WINC1500 configuration. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef CONF_WINC_H_INCLUDED +#define CONF_WINC_H_INCLUDED + +/* + --------------------------------- + ---------- PIN settings --------- + --------------------------------- + */ + +#define CONF_WINC_PIN_RESET IOPORT_CREATE_PIN(PIOA, 24) +#define CONF_WINC_PIN_CHIP_ENABLE IOPORT_CREATE_PIN(PIOA, 6) +#define CONF_WINC_PIN_WAKE IOPORT_CREATE_PIN(PIOA, 25) + +/* + --------------------------------- + ---------- SPI settings --------- + --------------------------------- + */ + +#define CONF_WINC_USE_SPI (1) + +/** SPI pin and instance settings. */ +#define CONF_WINC_SPI SPI +#define CONF_WINC_SPI_ID ID_SPI +#define CONF_WINC_SPI_MISO_GPIO SPI_MISO_GPIO +#define CONF_WINC_SPI_MISO_FLAGS SPI_MISO_FLAGS +#define CONF_WINC_SPI_MOSI_GPIO SPI_MOSI_GPIO +#define CONF_WINC_SPI_MOSI_FLAGS SPI_MOSI_FLAGS +#define CONF_WINC_SPI_CLK_GPIO SPI_SPCK_GPIO +#define CONF_WINC_SPI_CLK_FLAGS SPI_SPCK_FLAGS +#define CONF_WINC_SPI_CS_GPIO SPI_NPCS0_GPIO +#define CONF_WINC_SPI_CS_FLAGS PIO_OUTPUT_1 +#define CONF_WINC_SPI_NPCS (0) + +/** SPI delay before SPCK and between consecutive transfer. */ +#define CONF_WINC_SPI_DLYBS (0) +#define CONF_WINC_SPI_DLYBCT (0) + +/** SPI interrupt pin. */ +#define CONF_WINC_SPI_INT_PIN IOPORT_CREATE_PIN(PIOA, 1) +#define CONF_WINC_SPI_INT_PIO PIOA +#define CONF_WINC_SPI_INT_PIO_ID ID_PIOA +#define CONF_WINC_SPI_INT_MASK (1 << 1) +#define CONF_WINC_SPI_INT_PRIORITY (0) + +/** Clock polarity & phase. */ +#define CONF_WINC_SPI_POL (0) +#define CONF_WINC_SPI_PHA (1) + +/** SPI clock. */ +#define CONF_WINC_SPI_CLOCK (48000000) + +/* + --------------------------------- + --------- Debug Options --------- + --------------------------------- + */ +#include +#define CONF_WINC_DEBUG (0) +#define CONF_WINC_PRINTF printf + +#endif /* CONF_WINC_H_INCLUDED */ diff --git a/drivers/wifi/winc1500/winc1500.c b/drivers/wifi/winc1500/winc1500.c new file mode 100644 index 0000000000000..3dfbf11d827a6 --- /dev/null +++ b/drivers/wifi/winc1500/winc1500.c @@ -0,0 +1,849 @@ +/** + * Copyright (c) 2017 IpTronix + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define SYS_LOG_LEVEL CONFIG_SYS_LOG_ETHERNET_LEVEL +#define SYS_LOG_DOMAIN "dev/winc1500" +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "driver/include/m2m_wifi.h" +#include "socket/include/m2m_socket_host_if.h" + +#ifndef CONFIG_WINC1500_BUF_CTR +#define CONFIG_WINC1500_BUF_CTR 1 +#endif +#ifndef CONFIG_WINC1500_MAX_PACKET_SIZE +#define CONFIG_WINC1500_MAX_PACKET_SIZE 1500 +#endif +#ifndef CONFIG_WINC1500_THREAD_STACK_SIZE +#define CONFIG_WINC1500_THREAD_STACK_SIZE 5000 +#endif +#ifndef CONFIG_WINC1500_THREAD_PRIO +#define CONFIG_WINC1500_THREAD_PRIO 2 +#endif +#ifndef CONFIG_OFFLOAD_MAX_SOCKETS +#define CONFIG_OFFLOAD_MAX_SOCKETS 2 +#endif + +#define WINC1500_BIND_TIMEOUT 500 +#define WINC1500_LISTEN_TIMEOUT 500 + +NET_BUF_POOL_DEFINE(winc1500_tx_pool, CONFIG_WINC1500_BUF_CTR, + CONFIG_WINC1500_MAX_PACKET_SIZE, 0, NULL); +NET_BUF_POOL_DEFINE(winc1500_rx_pool, CONFIG_WINC1500_BUF_CTR, + CONFIG_WINC1500_MAX_PACKET_SIZE, 0, NULL); + +struct k_thread winc1500_thread_data; + +#if defined(CONFIG_SYS_LOG) && (SYS_LOG_LEVEL > SYS_LOG_LEVEL_OFF) + +static char *socket_error_string(s8_t err) +{ + switch (err) { + case SOCK_ERR_NO_ERROR: + return "Successful socket operation"; + case SOCK_ERR_INVALID_ADDRESS: + return "Socket address is invalid." + "The socket operation cannot be completed successfully without " + "specifying a specific address. " + "For example: bind is called without specifying a port number"; + case SOCK_ERR_ADDR_ALREADY_IN_USE: + return "Socket operation cannot bind on the given address." + " With socket operations, only one IP address per socket is " + "permitted." + "Any attempt for a new socket to bind with an IP address " + "already bound to another open socket, " + "will return the following error code. States that bind " + "operation failed."; + case SOCK_ERR_MAX_TCP_SOCK: + return "Exceeded the maximum number of TCP sockets." + "A maximum number of TCP sockets opened simultaneously is " + "defined through TCP_SOCK_MAX." + "It is not permitted to exceed that number at socket creation." + " Identifies that @ref socket operation failed."; + case SOCK_ERR_MAX_UDP_SOCK: + return "Exceeded the maximum number of UDP sockets." + "A maximum number of UDP sockets opened simultaneously is " + "defined through UDP_SOCK_MAX." + "It is not permitted to exceed that number at socket " + "creation. Identifies that socket operation failed"; + case SOCK_ERR_INVALID_ARG: + return "An invalid arguement is passed to a function."; + case SOCK_ERR_MAX_LISTEN_SOCK: + return "Exceeded the maximum number of TCP passive listening sockets." + "Identifies Identifies that listen operation failed."; + case SOCK_ERR_INVALID: + return "The requested socket operation is not valid in the current " + "socket state." + "For example: @ref accept is called on a TCP socket before " + "bind or listen."; + case SOCK_ERR_ADDR_IS_REQUIRED: + return "Destination address is required." + "Failure to provide the socket address required for the " + "socket operation to be completed." + "It is generated as an error to the sendto function when " + "the address required to send the data to is not known."; + case SOCK_ERR_CONN_ABORTED: + return "The socket is closed by the peer." + "The local socket is closed also."; + case SOCK_ERR_TIMEOUT: + return "The socket pending operation has timedout."; + case SOCK_ERR_BUFFER_FULL: + return "No buffer space available to be used for the requested " + "socket operation."; + default: + return "Unknown"; + } +} + +static char *wifi_cb_msg_2_str(u8_t message_type) +{ + switch (message_type) { + case M2M_WIFI_RESP_CURRENT_RSSI: + return "M2M_WIFI_RESP_CURRENT_RSSI"; + case M2M_WIFI_REQ_WPS: + return "M2M_WIFI_REQ_WPS"; + case M2M_WIFI_RESP_IP_CONFIGURED: + return "M2M_WIFI_RESP_IP_CONFIGURED"; + case M2M_WIFI_RESP_IP_CONFLICT: + return "M2M_WIFI_RESP_IP_CONFLICT"; + case M2M_WIFI_RESP_CLIENT_INFO: + return "M2M_WIFI_RESP_CLIENT_INFO"; + + case M2M_WIFI_RESP_GET_SYS_TIME: + return "M2M_WIFI_RESP_GET_SYS_TIME"; + case M2M_WIFI_REQ_SEND_ETHERNET_PACKET: + return "M2M_WIFI_REQ_SEND_ETHERNET_PACKET"; + case M2M_WIFI_RESP_ETHERNET_RX_PACKET: + return "M2M_WIFI_RESP_ETHERNET_RX_PACKET"; + + case M2M_WIFI_RESP_CON_STATE_CHANGED: + return "M2M_WIFI_RESP_CON_STATE_CHANGED"; + case M2M_WIFI_REQ_DHCP_CONF: + return "Response indicating that IP address was obtained."; + case M2M_WIFI_RESP_SCAN_DONE: + return "M2M_WIFI_RESP_SCAN_DONE"; + case M2M_WIFI_RESP_SCAN_RESULT: + return "M2M_WIFI_RESP_SCAN_RESULT"; + case M2M_WIFI_RESP_PROVISION_INFO: + return "M2M_WIFI_RESP_PROVISION_INFO"; + default: + return "UNKNOWN"; + } +} + +static char *socket_message_to_string(u8_t message) +{ + switch (message) { + case SOCKET_MSG_BIND: + return "Bind socket event."; + case SOCKET_MSG_LISTEN: + return "Listen socket event."; + case SOCKET_MSG_DNS_RESOLVE: + return "DNS Resolution event."; + case SOCKET_MSG_ACCEPT: + return "Accept socket event."; + case SOCKET_MSG_CONNECT: + return "Connect socket event."; + case SOCKET_MSG_RECV: + return "Receive socket event."; + case SOCKET_MSG_SEND: + return "Send socket event."; + case SOCKET_MSG_SENDTO: + return "Sendto socket event."; + case SOCKET_MSG_RECVFROM: + return "Recvfrom socket event."; + default: + return "UNKNOWN."; + } +} +#endif /* defined(CONFIG_SYS_LOG) && (SYS_LOG_LEVEL > SYS_LOG_LEVEL_OFF) */ + + +K_THREAD_STACK_MEMBER(winc1500_stack, CONFIG_WINC1500_THREAD_STACK_SIZE); + +/** + * + */ +struct winc1500_data { + struct wifi_context wifi_ctx; + struct socket_data { + struct net_context *context; + net_context_connect_cb_t connect_cb; + net_tcp_accept_cb_t accept_cb; + net_context_send_cb_t send_cb; + net_context_recv_cb_t recv_cb; + void *connect_user_data; + void *send_user_data; + void *recv_user_data; + void *accept_user_data; + struct net_pkt *rx_pkt; + struct net_buf *pkt_buf; + int ret_code; + struct k_sem wait_sem; + } socket_data[CONFIG_OFFLOAD_MAX_SOCKETS]; + struct net_if *iface; + unsigned char mac[6]; +}; + +static struct winc1500_data winc1500_data; + +/** + * This function is called when the socket is to be opened. + */ +static int winc1500_get(sa_family_t family, + enum net_sock_type type, + enum net_ip_protocol ip_proto, + struct net_context **context) +{ + if (family != AF_INET) { + SYS_LOG_ERR("Only AF_INET is supported!"); + return -1; + } + + (*context)->user_data = (void *)(sint32)socket(family, type, 0); + if ((*context)->user_data < 0) { + SYS_LOG_ERR("socket error!"); + return -1; + } + + k_sem_init(&winc1500_data.socket_data[(int)(*context)->user_data].wait_sem, + 0, 1); + + winc1500_data.socket_data[(int)(*context)->user_data].context = *context; + + return 0; +} + +/** + * This function is called when user wants to bind to local IP address. + */ +static int winc1500_bind(struct net_context *context, + const struct sockaddr *addr, + socklen_t addrlen) +{ + SOCKET socket = (int)context->user_data; + int ret; + + /* FIXME atmel winc1500 don't support bind on null port */ + if (net_sin(addr)->sin_port == 0) { + return 0; + } + + ret = bind((int)context->user_data, (struct sockaddr *)addr, addrlen); + if (ret) { + SYS_LOG_ERR("bind error %d %s!\n", ret, socket_message_to_string(ret)); + return ret; + } + if (k_sem_take(&winc1500_data.socket_data[socket].wait_sem, + WINC1500_BIND_TIMEOUT)) { + SYS_LOG_ERR("bind error timeout expired"); + return -ETIMEDOUT; + } + + return winc1500_data.socket_data[socket].ret_code; +} + +/** + * This function is called when user wants to mark the socket + * to be a listening one. + */ +static int winc1500_listen(struct net_context *context, int backlog) +{ + SOCKET socket = (int)context->user_data; + int ret; + + ret = listen((int)context->user_data, backlog); + if (ret) { + SYS_LOG_ERR("listen error %d %s!\n", ret, + socket_error_string(ret)); + return ret; + } + if (k_sem_take(&winc1500_data.socket_data[socket].wait_sem, + WINC1500_LISTEN_TIMEOUT)) { + return -ETIMEDOUT; + } + + return winc1500_data.socket_data[socket].ret_code; +} + +/** + * This function is called when user wants to create a connection + * to a peer host. + */ +static int winc1500_connect(struct net_context *context, + const struct sockaddr *addr, + socklen_t addrlen, + net_context_connect_cb_t cb, + int32_t timeout, + void *user_data) +{ + SOCKET socket = (int)context->user_data; + int ret; + + winc1500_data.socket_data[socket].connect_cb = cb; + winc1500_data.socket_data[socket].connect_user_data = user_data; + winc1500_data.socket_data[socket].ret_code = 0; + + ret = connect(socket, (struct sockaddr *)addr, addrlen); + if (ret) { + SYS_LOG_ERR("connect error %d %s!\n", ret, + socket_error_string(ret)); + return ret; + } + + if (timeout != 0 && + k_sem_take(&winc1500_data.socket_data[socket].wait_sem, timeout)) { + return -ETIMEDOUT; + } + + return winc1500_data.socket_data[socket].ret_code; +} + +/** + * This function is called when user wants to accept a connection + * being established. + */ +static int winc1500_accept(struct net_context *context, + net_tcp_accept_cb_t cb, + int32_t timeout, + void *user_data) +{ + SOCKET socket = (int)context->user_data; + int ret; + + winc1500_data.socket_data[socket].accept_cb = cb; + + ret = accept(socket, NULL, 0); + if (ret) { + SYS_LOG_ERR("accept error %d %s!\n", ret, + socket_error_string(ret)); + return ret; + } + + if (timeout) { + if (k_sem_take(&winc1500_data.socket_data[socket].wait_sem, timeout)) { + return -ETIMEDOUT; + } + } else { + k_sem_take(&winc1500_data.socket_data[socket].wait_sem, K_FOREVER); + } + + return winc1500_data.socket_data[socket].ret_code; +} + +/** + * This function is called when user wants to send data to peer host. + */ +static int winc1500_send(struct net_pkt *pkt, + net_context_send_cb_t cb, + int32_t timeout, + void *token, + void *user_data) +{ + struct net_context *context = pkt->context; + SOCKET socket = (int)context->user_data; + bool first_frag; + struct net_buf *frag; + int ret; + + winc1500_data.socket_data[socket].send_cb = cb; + winc1500_data.socket_data[socket].send_user_data = user_data; + + first_frag = true; + + for (frag = pkt->frags; frag; frag = frag->frags) { + u8_t *data_ptr; + u16_t data_len; + if (first_frag) { + data_ptr = net_pkt_ll(pkt); + data_len = net_pkt_ll_reserve(pkt) + frag->len; + first_frag = false; + } else { + data_ptr = frag->data; + data_len = frag->len; + } + ret = send(socket, data_ptr, data_len, 0); + if (ret) { + SYS_LOG_ERR("send error %d %s!\n", ret, + socket_error_string(ret)); + return ret; + } + } + + net_pkt_unref(pkt); + + return 0; +} + +/** + * This function is called when user wants to send data to peer host. + */ +static int winc1500_sendto(struct net_pkt *pkt, + const struct sockaddr *dst_addr, + socklen_t addrlen, + net_context_send_cb_t cb, + int32_t timeout, + void *token, + void *user_data) +{ + struct net_context *context = pkt->context; + SOCKET socket = (int)context->user_data; + bool first_frag; + struct net_buf *frag; + int ret; + + winc1500_data.socket_data[socket].send_cb = cb; + winc1500_data.socket_data[socket].send_user_data = user_data; + + first_frag = true; + + for (frag = pkt->frags; frag; frag = frag->frags) { + u8_t *data_ptr; + u16_t data_len; + if (first_frag) { + data_ptr = net_pkt_ll(pkt); + data_len = net_pkt_ll_reserve(pkt) + frag->len; + first_frag = false; + } else { + data_ptr = frag->data; + data_len = frag->len; + } + ret = sendto(socket, data_ptr, data_len, 0, (struct sockaddr *)dst_addr, addrlen); + if (ret) { + SYS_LOG_ERR("send error %d %s!\n", ret, + socket_error_string(ret)); + return ret; + } + } + + net_pkt_unref(pkt); + + return 0; +} + +/** + */ +static int prepare_pkt(struct socket_data *sock_data) +{ + /* Get the frame from the buffer */ + sock_data->rx_pkt = net_pkt_get_reserve_rx(0, K_NO_WAIT); + if (!sock_data->rx_pkt) { + SYS_LOG_ERR("Could not allocate rx packet"); + return -1; + } + + /* Reserve a data frag to receive the frame */ + sock_data->pkt_buf = net_pkt_get_frag(sock_data->rx_pkt, K_NO_WAIT); + if (!sock_data->pkt_buf) { + net_pkt_unref(sock_data->rx_pkt); + SYS_LOG_ERR("Could not allocate data frag"); + return -1; + } + + net_pkt_frag_insert(sock_data->rx_pkt, sock_data->pkt_buf); + + return 0; +} +/** + * This function is called when user wants to receive data from peer + * host. + */ +static int winc1500_recv(struct net_context *context, + net_context_recv_cb_t cb, + int32_t timeout, + void *user_data) +{ + SOCKET socket = (int) context->user_data; + int ret; + + ret = prepare_pkt(&winc1500_data.socket_data[socket]); + if (ret) { + SYS_LOG_ERR("Could not reserve packet buffer"); + return -ENOMEM; + } + + winc1500_data.socket_data[socket].recv_cb = cb; + winc1500_data.socket_data[socket].recv_user_data = user_data; + + ret = recv(socket, winc1500_data.socket_data[socket].pkt_buf->data, + CONFIG_WINC1500_MAX_PACKET_SIZE, timeout); + if (ret) { + SYS_LOG_ERR("recv error %d %s!\n", ret, + socket_error_string(ret)); + return ret; + } + + return 0; +} + +/** + * This function is called when user wants to close the socket. + */ +static int winc1500_put(struct net_context *context) +{ + return 0; +} + +static struct net_offload winc1500_offload = { + .get = winc1500_get, + .bind = winc1500_bind, + .listen = winc1500_listen, + .connect = winc1500_connect, + .accept = winc1500_accept, + .send = winc1500_send, + .sendto = winc1500_sendto, + .recv = winc1500_recv, + .put = winc1500_put, +}; + +static int winc1500_ap_connect(struct device *dev, char *ssid, + wifi_security_t sec_type, char *psk) +{ + int ret; + u8_t winc1500_sec; + + NET_INFO("net_if_ap_connect:m2m_wifi_connect SSID:%s, PSK:%s\n", ssid, psk); + + if (sec_type & WEP) { + winc1500_sec = M2M_WIFI_SEC_WEP; + } else if (sec_type & (WPA | WPA2)) { + winc1500_sec = M2M_WIFI_SEC_WPA_PSK; + } else if (sec_type & ENTERPRISE) { + winc1500_sec = M2M_WIFI_SEC_802_1X; + } else if (sec_type == WIFI_SECURITY_OPEN) { + winc1500_sec = M2M_WIFI_SEC_OPEN; + } else { + winc1500_sec = M2M_WIFI_SEC_INVALID; + } + + ret = m2m_wifi_connect((char *)ssid, strlen(ssid), + winc1500_sec, (void *)psk, M2M_WIFI_CH_ALL); + if (ret) { + /* status = TODO update status to not connected / connection error */ + NET_ERR("net_if_ap_connect:ERROR %d\n", ret); + } else { + /* status = TODO update status to connected */ + NET_INFO("net_if_ap_connect:OK\n"); + } + return ret; +} + +static int winc1500_scan(struct device *dev) +{ + return 0; +} + +static int winc1500_ap_disconnect(struct device *dev) +{ + return m2m_wifi_disconnect(); +} + +static void winc1500_wifi_cb(u8_t message_type, void *pvMsg) +{ + SYS_LOG_INF("winc1500_wifi_cb: Msg Type %d %s\n", message_type, wifi_cb_msg_2_str(message_type)); + + switch (message_type) { + case M2M_WIFI_RESP_CON_STATE_CHANGED: + { + tstrM2mWifiStateChanged *pstrWifiState = (tstrM2mWifiStateChanged *)pvMsg; + + switch (pstrWifiState->u8CurrState) { + case M2M_WIFI_DISCONNECTED: /*!< Wi-Fi state is disconnected. */ + /* TODO status disconnected */ + break; + case M2M_WIFI_CONNECTED: /*!< Wi-Fi state is connected. */ + /* TODO status connected */ + break; + case M2M_WIFI_UNDEF: /*!< Undefined Wi-Fi State. */ + /* TODO status undefined*/ + break; + } + } + break; + + case M2M_WIFI_REQ_DHCP_CONF: + { + u8_t *pu8IPAddress = (u8_t *)pvMsg; + struct in_addr addr; + u8_t i; + + /* Connected and got IP address*/ + printk("winc1500_wifi_cb:Wi-Fi connected, IP is %u.%u.%u.%u\n", + pu8IPAddress[0], pu8IPAddress[1], pu8IPAddress[2], pu8IPAddress[3]); + NET_INFO("winc1500_wifi_cb:Wi-Fi connected, IP is %u.%u.%u.%u\n", + pu8IPAddress[0], pu8IPAddress[1], pu8IPAddress[2], pu8IPAddress[3]); + /* TODO at this point the standby mode should be enable */ + /* status = WiFi connected IP assigned */ + for (i = 0; i < 4; i++) { + addr.s4_addr[i] = pu8IPAddress[i]; + } + + /* TODO fill in net mask, gateway and lease time */ + + net_if_ipv4_addr_add(winc1500_data.iface, + &addr, + NET_ADDR_DHCP, + 0); + } + break; + + default: + break; + } + +} + +static void winc1500_socket_cb(SOCKET sock, uint8 message, void *pvMsg) +{ + if (message != 6) { + SYS_LOG_INF("winc1500_socket_cb: sock %d Msg %d %s\n", + sock, message, socket_message_to_string(message)); + } + + winc1500_data.socket_data[sock].ret_code = 0; + + switch (message) { + case SOCKET_MSG_CONNECT: + { + tstrSocketConnectMsg *strConnMsg = (tstrSocketConnectMsg *)pvMsg; + SYS_LOG_ERR("winc1500_socket_cb:CONNECT: socket %d error %d\n", + strConnMsg->sock, strConnMsg->s8Error); + if (winc1500_data.socket_data[sock].connect_cb) { + winc1500_data.socket_data[sock].connect_cb( + winc1500_data.socket_data[sock].context, + strConnMsg->s8Error, + winc1500_data.socket_data[sock].connect_user_data); + } + winc1500_data.socket_data[sock].ret_code = strConnMsg->s8Error; + } + k_sem_give(&winc1500_data.socket_data[sock].wait_sem); + break; + + case SOCKET_MSG_SEND: + break; + + case SOCKET_MSG_RECV: + { + tstrSocketRecvMsg *pstrRx = (tstrSocketRecvMsg *)pvMsg; + + if ((pstrRx->pu8Buffer != NULL) && (pstrRx->s16BufferSize > 0)) { + + net_buf_add(winc1500_data.socket_data[sock].pkt_buf, + pstrRx->s16BufferSize); + + net_pkt_set_appdata(winc1500_data.socket_data[sock].rx_pkt, + winc1500_data.socket_data[sock].pkt_buf->data); + net_pkt_set_appdatalen(winc1500_data.socket_data[sock].rx_pkt, + pstrRx->s16BufferSize); + + if (winc1500_data.socket_data[sock].recv_cb) { + winc1500_data.socket_data[sock].recv_cb( + winc1500_data.socket_data[sock].context, + winc1500_data.socket_data[sock].rx_pkt, + 0, + winc1500_data.socket_data[sock].recv_user_data); + } + } else if (pstrRx->pu8Buffer == NULL) { + if (pstrRx->s16BufferSize == SOCK_ERR_CONN_ABORTED) { + net_pkt_unref(winc1500_data.socket_data[sock].rx_pkt); + return; + } + } + + if (prepare_pkt(&winc1500_data.socket_data[sock])) { + SYS_LOG_ERR("Could not reserve packet buffer"); + return; + } + + recv(sock, winc1500_data.socket_data[sock].pkt_buf->data, + CONFIG_WINC1500_MAX_PACKET_SIZE, K_NO_WAIT); + } + break; + case SOCKET_MSG_BIND: + { + /* The result of the bind operation. + * Holding a value of ZERO for a successful bind or otherwise a negative + * error code corresponding to the type of error. + */ + tstrSocketBindMsg *bind_msg = (tstrSocketBindMsg *)pvMsg; + if (bind_msg->status) { + SYS_LOG_ERR("winc1500_socket_cb:BIND: error %d %s\n", + bind_msg->status, + socket_message_to_string(bind_msg->status)); + winc1500_data.socket_data[sock].ret_code = bind_msg->status; + } + } + k_sem_give(&winc1500_data.socket_data[sock].wait_sem); + break; + case SOCKET_MSG_LISTEN: + { + /* Holding a value of ZERO for a successful listen or + * otherwise a negative error code corresponding to + * the type of error. + */ + tstrSocketListenMsg *listen_msg = (tstrSocketListenMsg *)pvMsg; + + if (listen_msg->status) { + SYS_LOG_ERR("winc1500_socket_cb:LISTEN: error %d %s\n", + listen_msg->status, + socket_message_to_string(listen_msg->status)); + winc1500_data.socket_data[sock].ret_code = listen_msg->status; + } + } + k_sem_give(&winc1500_data.socket_data[sock].wait_sem); + break; + case SOCKET_MSG_ACCEPT: + { + /* sock + * On a successful accept operation, the return information is + * the socket ID for the accepted connection with the remote peer. + * Otherwise a negative error code is returned to indicate failure + * of the accept operation. + * strAddr; + * Socket address structure for the remote peer. + */ + tstrSocketAcceptMsg *accept_msg = (tstrSocketAcceptMsg *)pvMsg; + + NET_INFO("winc1500_socket_cb:ACCEPT:" + "from %d.%d.%d.%d:%d, new socket is %d\n", + accept_msg->strAddr.sin_addr.s4_addr[0], + accept_msg->strAddr.sin_addr.s4_addr[1], + accept_msg->strAddr.sin_addr.s4_addr[2], + accept_msg->strAddr.sin_addr.s4_addr[3], + ntohs(accept_msg->strAddr.sin_port), + accept_msg->sock); + if (accept_msg->sock < 0) { + SYS_LOG_ERR("winc1500_socket_cb:ACCEPT: error %d %s\n", + accept_msg->sock, socket_message_to_string(accept_msg->sock)); + winc1500_data.socket_data[sock].ret_code = accept_msg->sock; + } + if (winc1500_data.socket_data[sock].accept_cb) { + int ret; + + memcpy((void *)&winc1500_data.socket_data[accept_msg->sock], + (void *)&winc1500_data.socket_data[sock], + sizeof(struct socket_data)); + + ret = net_context_get(AF_INET, SOCK_STREAM, IPPROTO_TCP, + &winc1500_data.socket_data[accept_msg->sock].context); + if (ret < 0) { + NET_ERR("Cannot get new network context for ACCEPT"); + } else { + winc1500_data.socket_data[accept_msg->sock].context->user_data = + (void *)((int)accept_msg->sock); + + winc1500_data.socket_data[sock].accept_cb( + winc1500_data.socket_data[accept_msg->sock].context, + (struct sockaddr *)&accept_msg->strAddr, + sizeof(struct sockaddr_in), + (accept_msg->sock > 0) ? 0 : accept_msg->sock, + winc1500_data.socket_data[sock].accept_user_data); + } + } + } + k_sem_give(&winc1500_data.socket_data[sock].wait_sem); + break; + } +} + +static void winc1500_iface_init(struct net_if *iface) +{ + struct device *dev = net_if_get_device(iface); + struct winc1500_data *context = dev->driver_data; + + SYS_LOG_DBG(""); + + NET_INFO("eth_init:net_if_set_link_addr:" + "MAC Address %02X:%02X:%02X:%02X:%02X:%02X\n", + context->mac[0], context->mac[1], context->mac[2], + context->mac[3], context->mac[4], context->mac[5]); + + net_if_set_link_addr(iface, context->mac, sizeof(context->mac), + NET_LINK_ETHERNET); + + iface->offload = &winc1500_offload; + + context->iface = iface; +} + +static const struct wifi_api winc1500_api = { + .iface_api.init = winc1500_iface_init, + .scan = winc1500_scan, + .ap_connect = winc1500_ap_connect, + .ap_disconnect = winc1500_ap_disconnect, +}; + +static void winc1500_thread(void *arg1, void *unused1, void *unused2) +{ + ARG_UNUSED(arg1); + ARG_UNUSED(unused1); + ARG_UNUSED(unused2); + + while (1) { + /* Handle the app state machine plus the WINC event handler */ + while (m2m_wifi_handle_events(NULL) != 0) { + } + k_sleep(K_MSEC(1)); + } +} + +static int winc1500_init(struct device *dev) +{ + struct winc1500_data *context = dev->driver_data; + tstrWifiInitParam param; + int ret; + + memset((void *)¶m, 0, sizeof(param)); + param.pfAppWifiCb = winc1500_wifi_cb; + ret = m2m_wifi_init(¶m); + if (ret) { + SYS_LOG_ERR("m2m_wifi_init return error!(%d)\n", ret); + return -1; + } + + socketInit(); + registerSocketCallback(winc1500_socket_cb, NULL); + + unsigned char IsValid; + m2m_wifi_get_otp_mac_address(context->mac, &IsValid); + SYS_LOG_INF("WINC1500 MAC Address from OTP (%d) " + "%02X:%02X:%02X:%02X:%02X:%02X\n", + IsValid, + context->mac[0], context->mac[1], context->mac[2], + context->mac[3], context->mac[4], context->mac[5]); + + m2m_wifi_set_power_profile(PWR_LOW1); + m2m_wifi_set_tx_power(TX_PWR_LOW); + + /* monitoring thread for winc wifi callbacks */ + k_thread_create(&winc1500_thread_data, winc1500_stack, + CONFIG_WINC1500_THREAD_STACK_SIZE, + winc1500_thread, (void *)dev, NULL, NULL, + K_PRIO_COOP(CONFIG_WINC1500_THREAD_PRIO), + 0, K_NO_WAIT); + + SYS_LOG_INF("WINC1500 eth driver Initialized"); + return 0; +} + +NET_DEVICE_OFFLOAD_INIT(winc1500_0, "WINC1500_0", + winc1500_init, &winc1500_data, NULL, + CONFIG_WIFI_INIT_PRIORITY, &winc1500_api, + CONFIG_WINC1500_MAX_PACKET_SIZE); diff --git a/ext/Kbuild b/ext/Kbuild index bb1817818faec..18a00c59ce556 100644 --- a/ext/Kbuild +++ b/ext/Kbuild @@ -2,3 +2,4 @@ obj-y += hal/ obj-y += lib/ obj-y += fs/ obj-y += debug/ +obj-y += drivers/atmel/winc1500/ diff --git a/ext/Kconfig b/ext/Kconfig index b6b488c14f1f8..9c36029922980 100644 --- a/ext/Kconfig +++ b/ext/Kconfig @@ -16,4 +16,6 @@ source "ext/fs/Kconfig" source "ext/debug/Kconfig" +source "ext/drivers/atmel/winc1500/Kconfig" + endmenu diff --git a/ext/Makefile b/ext/Makefile index b51f7a2ac0f61..a4d100f5e3665 100644 --- a/ext/Makefile +++ b/ext/Makefile @@ -2,3 +2,4 @@ include $(srctree)/ext/lib/Makefile include $(srctree)/ext/hal/Makefile include $(srctree)/ext/fs/Makefile include $(srctree)/ext/debug/Makefile +include $(srctree)/ext/drivers/atmel/winc1500/Makefile diff --git a/ext/drivers/atmel/winc1500/Kconfig b/ext/drivers/atmel/winc1500/Kconfig new file mode 100644 index 0000000000000..d12af30076c8c --- /dev/null +++ b/ext/drivers/atmel/winc1500/Kconfig @@ -0,0 +1,9 @@ +# Kconfig - Atmel WINC1500 configuration options +# +# WINC1500 options +# + +# menuconfig NETWORKING_WITH_WINC1500 +# bool +# prompt "WINC1500 driver Configuration" +# default n diff --git a/ext/drivers/atmel/winc1500/Makefile b/ext/drivers/atmel/winc1500/Makefile new file mode 100644 index 0000000000000..b4d399424451b --- /dev/null +++ b/ext/drivers/atmel/winc1500/Makefile @@ -0,0 +1,17 @@ +ZEPHYRINCLUDE +=-I${srctree}/ext/drivers/atmel/winc1500/ +ZEPHYRINCLUDE +=-I${srctree}/drivers/wifi/winc1500/ + +obj-$(CONFIG_WIFI_WINC1500) += \ + driver/source/m2m_ate_mode.o \ + driver/source/m2m_crypto.o \ + driver/source/m2m_hif.o \ + driver/source/m2m_ota.o \ + driver/source/m2m_periph.o \ + driver/source/m2m_wifi.o \ + driver/source/nmasic.o \ + driver/source/nmbus.o \ + driver/source/nmdrv.o \ + driver/source/nmspi.o \ + socket/source/socket.o \ + common/source/nm_common.o \ + spi_flash/source/spi_flash.o \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/README b/ext/drivers/atmel/winc1500/README new file mode 100644 index 0000000000000..3e20b2797aceb --- /dev/null +++ b/ext/drivers/atmel/winc1500/README @@ -0,0 +1,38 @@ +Atmel WINC1500 driver in Zephyr is an extraction of the Atmel ASF library. +The original upstream code can be found at: + +http://asf.atmel.com/docs/latest/download.html + +At revision 3.33.0 + +Any changes to the local version should include Zephyr's TinyCrypt +maintainer in the review. That can be found via the git history. + +The following is the license information for this code: + +Copyright (c) 2016 Atmel Corporation. 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. The name of Atmel may not be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED +WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE +EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS +OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, +STRICT LIABILITY, OR TORT (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/ext/drivers/atmel/winc1500/common/include/nm_common.h b/ext/drivers/atmel/winc1500/common/include/nm_common.h new file mode 100755 index 0000000000000..56b37c567752c --- /dev/null +++ b/ext/drivers/atmel/winc1500/common/include/nm_common.h @@ -0,0 +1,156 @@ +/** + * + * \file + * + * \brief WINC Driver Common API Declarations. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NM_COMMON_H_ +#define _NM_COMMON_H_ + +#include "bsp/include/nm_bsp.h" +#include "common/include/nm_types.h" +#include "common/include/nm_debug.h" + +/**@defgroup CommonDefines CommonDefines + * @ingroup WlanDefines + */ +/**@{*/ +#define M2M_TIME_OUT_DELAY 10000 + +/*states*/ +#define M2M_SUCCESS ((sint8)0) +#define M2M_ERR_SEND ((sint8)-1) +#define M2M_ERR_RCV ((sint8)-2) +#define M2M_ERR_MEM_ALLOC ((sint8)-3) +#define M2M_ERR_TIME_OUT ((sint8)-4) +#define M2M_ERR_INIT ((sint8)-5) +#define M2M_ERR_BUS_FAIL ((sint8)-6) +#define M2M_NOT_YET ((sint8)-7) +#define M2M_ERR_FIRMWARE ((sint8)-8) +#define M2M_SPI_FAIL ((sint8)-9) +#define M2M_ERR_FIRMWARE_bURN ((sint8)-10) +#define M2M_ACK ((sint8)-11) +#define M2M_ERR_FAIL ((sint8)-12) +#define M2M_ERR_FW_VER_MISMATCH ((sint8)-13) +#define M2M_ERR_SCAN_IN_PROGRESS ((sint8)-14) +/* +Invalid argument +*/ +#define M2M_ERR_INVALID_ARG ((sint8)-15) + +/*i2c MAASTER ERR*/ +#define I2C_ERR_LARGE_ADDRESS 0xE1UL /*the address exceed the max addressing mode in i2c flash*/ +#define I2C_ERR_TX_ABRT 0xE2UL /*NO ACK from slave*/ +#define I2C_ERR_OVER_SIZE 0xE3UL /**/ +#define ERR_PREFIX_NMIS 0xE4UL /*wrong first four byte in flash NMIS*/ +#define ERR_FIRMEWARE_EXCEED_SIZE 0xE5UL /*Total size of firmware exceed the max size 256k*/ +/**/ +#define PROGRAM_START 0x26961735UL +#define BOOT_SUCCESS 0x10add09eUL +#define BOOT_START 0x12345678UL + + +#define NBIT31 (0x80000000) +#define NBIT30 (0x40000000) +#define NBIT29 (0x20000000) +#define NBIT28 (0x10000000) +#define NBIT27 (0x08000000) +#define NBIT26 (0x04000000) +#define NBIT25 (0x02000000) +#define NBIT24 (0x01000000) +#define NBIT23 (0x00800000) +#define NBIT22 (0x00400000) +#define NBIT21 (0x00200000) +#define NBIT20 (0x00100000) +#define NBIT19 (0x00080000) +#define NBIT18 (0x00040000) +#define NBIT17 (0x00020000) +#define NBIT16 (0x00010000) +#define NBIT15 (0x00008000) +#define NBIT14 (0x00004000) +#define NBIT13 (0x00002000) +#define NBIT12 (0x00001000) +#define NBIT11 (0x00000800) +#define NBIT10 (0x00000400) +#define NBIT9 (0x00000200) +#define NBIT8 (0x00000100) +#define NBIT7 (0x00000080) +#define NBIT6 (0x00000040) +#define NBIT5 (0x00000020) +#define NBIT4 (0x00000010) +#define NBIT3 (0x00000008) +#define NBIT2 (0x00000004) +#define NBIT1 (0x00000002) +#define NBIT0 (0x00000001) + +#define M2M_MAX(A,B) ((A) > (B) ? (A) : (B)) +#define M2M_SEL(x,m1,m2,m3) ((x>1)?((x>2)?(m3):(m2)):(m1)) +#define WORD_ALIGN(val) (((val) & 0x03) ? ((val) + 4 - ((val) & 0x03)) : (val)) + + + +#define DATA_PKT_OFFSET 4 + +#ifndef BIG_ENDIAN +#define BYTE_0(word) ((uint8)(((word) >> 0 ) & 0x000000FFUL)) +#define BYTE_1(word) ((uint8)(((word) >> 8 ) & 0x000000FFUL)) +#define BYTE_2(word) ((uint8)(((word) >> 16) & 0x000000FFUL)) +#define BYTE_3(word) ((uint8)(((word) >> 24) & 0x000000FFUL)) +#else +#define BYTE_0(word) ((uint8)(((word) >> 24) & 0x000000FFUL)) +#define BYTE_1(word) ((uint8)(((word) >> 16) & 0x000000FFUL)) +#define BYTE_2(word) ((uint8)(((word) >> 8 ) & 0x000000FFUL)) +#define BYTE_3(word) ((uint8)(((word) >> 0 ) & 0x000000FFUL)) +#endif + +/**@}*/ +#ifdef __cplusplus + extern "C" { + #endif +NMI_API void m2m_memcpy(uint8* pDst,uint8* pSrc,uint32 sz); +NMI_API void m2m_memset(uint8* pBuf,uint8 val,uint32 sz); +NMI_API uint16 m2m_strlen(uint8 * pcStr); +NMI_API sint8 m2m_memcmp(uint8 *pu8Buff1,uint8 *pu8Buff2 ,uint32 u32Size); +NMI_API uint8 m2m_strncmp(uint8 *pcS1, uint8 *pcS2, uint16 u16Len); +NMI_API uint8 * m2m_strstr(uint8 *pcIn, uint8 *pcStr); +NMI_API uint8 m2m_checksum(uint8* buf, int sz); + +#ifdef __cplusplus +} + #endif +#endif /*_NM_COMMON_H_*/ diff --git a/ext/drivers/atmel/winc1500/common/include/nm_debug.h b/ext/drivers/atmel/winc1500/common/include/nm_debug.h new file mode 100755 index 0000000000000..5bbe02dcf0409 --- /dev/null +++ b/ext/drivers/atmel/winc1500/common/include/nm_debug.h @@ -0,0 +1,95 @@ +/** + * + * \file + * + * \brief This module contains debug APIs declarations. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NM_DEBUG_H_ +#define _NM_DEBUG_H_ + +#include "bsp/include/nm_bsp.h" +#include "bsp/include/nm_bsp_internal.h" + +/**@defgroup DebugDefines DebugDefines + * @ingroup WlanDefines + */ +/**@{*/ + + +#define M2M_LOG_NONE 0 +#define M2M_LOG_ERROR 1 +#define M2M_LOG_INFO 2 +#define M2M_LOG_REQ 3 +#define M2M_LOG_DBG 4 + +#if (defined __APS3_CORTUS__) +#define M2M_LOG_LEVEL M2M_LOG_ERROR +#else +#define M2M_LOG_LEVEL M2M_LOG_REQ +#endif + + +#define M2M_ERR(...) +#define M2M_INFO(...) +#define M2M_REQ(...) +#define M2M_DBG(...) +#define M2M_PRINT(...) + +#if (CONF_WINC_DEBUG == 1) +#undef M2M_PRINT +#define M2M_PRINT(...) do{CONF_WINC_PRINTF(__VA_ARGS__);CONF_WINC_PRINTF("\r");}while(0) +#if (M2M_LOG_LEVEL >= M2M_LOG_ERROR) +#undef M2M_ERR +#define M2M_ERR(...) do{CONF_WINC_PRINTF("(APP)(ERR)[%s][%d]",__FUNCTION__,__LINE__); CONF_WINC_PRINTF(__VA_ARGS__);CONF_WINC_PRINTF("\r");}while(0) +#if (M2M_LOG_LEVEL >= M2M_LOG_INFO) +#undef M2M_INFO +#define M2M_INFO(...) do{CONF_WINC_PRINTF("(APP)(INFO)"); CONF_WINC_PRINTF(__VA_ARGS__);CONF_WINC_PRINTF("\r");}while(0) +#if (M2M_LOG_LEVEL >= M2M_LOG_REQ) +#undef M2M_REQ +#define M2M_REQ(...) do{CONF_WINC_PRINTF("(APP)(R)"); CONF_WINC_PRINTF(__VA_ARGS__);CONF_WINC_PRINTF("\r");}while(0) +#if (M2M_LOG_LEVEL >= M2M_LOG_DBG) +#undef M2M_DBG +#define M2M_DBG(...) do{CONF_WINC_PRINTF("(APP)(DBG)[%s][%d]",__FUNCTION__,__LINE__); CONF_WINC_PRINTF(__VA_ARGS__);CONF_WINC_PRINTF("\r");}while(0) +#endif /*M2M_LOG_DBG*/ +#endif /*M2M_LOG_REQ*/ +#endif /*M2M_LOG_INFO*/ +#endif /*M2M_LOG_ERROR*/ +#endif /*CONF_WINC_DEBUG */ + +/**@}*/ +#endif /* _NM_DEBUG_H_ */ diff --git a/ext/drivers/atmel/winc1500/common/include/nm_types.h b/ext/drivers/atmel/winc1500/common/include/nm_types.h new file mode 100644 index 0000000000000..b5cf98351008d --- /dev/null +++ b/ext/drivers/atmel/winc1500/common/include/nm_types.h @@ -0,0 +1,91 @@ +/* + * nm_types.h + * + * Created on: May 8, 2017 + * Author: max + */ + +#ifndef ZEPHYR_EXT_DRIVERS_ATMEL_WINC1500_COMMON_INCLUDE_NM_TYPES_H_ +#define ZEPHYR_EXT_DRIVERS_ATMEL_WINC1500_COMMON_INCLUDE_NM_TYPES_H_ + +/*!< + * Attribute used to define memory section to map Functions in host memory. + */ +#define CONST const +/*!< + * Used for code portability. + */ + + +#define BSP_MIN(x, y) ((x) > (y)?(y):(x)) +/*!< + * Computes the minimum of \b x and \b y. + */ + + +/**@defgroup DataT DataTypes + * @ingroup nm_bsp + * @{ + */ + +/*! + * @ingroup DataTypes + * @typedef unsigned char uint8; + * @brief Range of values between 0 to 255 + */ +typedef unsigned char uint8; + +/*! + * @ingroup DataTypes + * @typedef unsigned short uint16; + * @brief Range of values between 0 to 65535 + */ +typedef unsigned short uint16; + +/*! + * @ingroup Data Types + * @typedef unsigned long uint32; + * @brief Range of values between 0 to 4294967295 + */ +typedef unsigned long uint32; + + +/*! + * @ingroup Data Types + * @typedef signed char sint8; + * @brief Range of values between -128 to 127 + */ +typedef signed char sint8; + +/*! + * @ingroup DataTypes + * @typedef signed short sint16; + * @brief Range of values between -32768 to 32767 + */ +typedef signed short sint16; + +/*! + * @ingroup DataTypes + * @typedef signed long sint32; + * @brief Range of values between -2147483648 to 2147483647 + */ + +typedef signed long sint32; + + + +#ifdef _NM_BSP_BIG_END +#define NM_BSP_B_L_32(x) \ +((((x) & 0x000000FF) << 24) + \ +(((x) & 0x0000FF00) << 8) + \ +(((x) & 0x00FF0000) >> 8) + \ +(((x) & 0xFF000000) >> 24)) +#define NM_BSP_B_L_16(x) \ +((((x) & 0x00FF) << 8) + \ +(((x) & 0xFF00) >> 8)) +#else +#define NM_BSP_B_L_32(x) (x) +#define NM_BSP_B_L_16(x) (x) +#endif + +#endif /* ZEPHYR_EXT_DRIVERS_ATMEL_WINC1500_COMMON_INCLUDE_NM_TYPES_H_ */ diff --git a/ext/drivers/atmel/winc1500/common/source/nm_common.c b/ext/drivers/atmel/winc1500/common/source/nm_common.c new file mode 100755 index 0000000000000..8b3c941c50380 --- /dev/null +++ b/ext/drivers/atmel/winc1500/common/source/nm_common.c @@ -0,0 +1,136 @@ +/** + * + * \file + * + * \brief This module contains common APIs declarations. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +#include "common/include/nm_common.h" + +void m2m_memcpy(uint8* pDst,uint8* pSrc,uint32 sz) +{ + if(sz == 0) return; + do + { + *pDst = *pSrc; + pDst++; + pSrc++; + }while(--sz); +} +uint8 m2m_checksum(uint8* buf, int sz) +{ + uint8 cs = 0; + while(--sz) + { + cs ^= *buf; + buf++; + } + + return cs; +} + +void m2m_memset(uint8* pBuf,uint8 val,uint32 sz) +{ + if(sz == 0) return; + do + { + *pBuf = val; + pBuf++; + }while(--sz); +} + +uint16 m2m_strlen(uint8 * pcStr) +{ + uint16 u16StrLen = 0; + while(*pcStr) + { + u16StrLen ++; + pcStr++; + } + return u16StrLen; +} + +uint8 m2m_strncmp(uint8 *pcS1, uint8 *pcS2, uint16 u16Len) +{ + for ( ; u16Len > 0; pcS1++, pcS2++, --u16Len) + if (*pcS1 != *pcS2) + return ((*(uint8 *)pcS1 < *(uint8 *)pcS2) ? -1 : +1); + else if (*pcS1 == '\0') + return 0; + return 0; +} + +/* Finds the occurance of pcStr in pcIn. +If pcStr is part of pcIn it returns a valid pointer to the start of pcStr within pcIn. +Otherwise a NULL Pointer is returned. +*/ +uint8 * m2m_strstr(uint8 *pcIn, uint8 *pcStr) +{ + uint8 u8c; + uint16 u16StrLen; + + u8c = *pcStr++; + if (!u8c) + return (uint8 *) pcIn; // Trivial empty string case + + u16StrLen = m2m_strlen(pcStr); + do { + uint8 u8Sc; + + do { + u8Sc = *pcIn++; + if (!u8Sc) + return (uint8 *) 0; + } while (u8Sc != u8c); + } while (m2m_strncmp(pcIn, pcStr, u16StrLen) != 0); + + return (uint8 *) (pcIn - 1); +} + +sint8 m2m_memcmp(uint8 *pu8Buff1,uint8 *pu8Buff2 ,uint32 u32Size) +{ + uint32 i; + sint8 s8Result = 0; + for(i = 0 ; i < u32Size ; i++) + { + if(pu8Buff1[i] != pu8Buff2[i]) + { + s8Result = 1; + break; + } + } + return s8Result; +} diff --git a/ext/drivers/atmel/winc1500/driver/include/m2m_ate_mode.h b/ext/drivers/atmel/winc1500/driver/include/m2m_ate_mode.h new file mode 100755 index 0000000000000..fca161b00a537 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/include/m2m_ate_mode.h @@ -0,0 +1,619 @@ +/** + * + * \file + * + * \brief WINC ATE Test Driver Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifdef _M2M_ATE_FW_ + +#ifndef _M2M_ATE_MODE_H_ +#define _M2M_ATE_MODE_H_ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#include "common/include/nm_common.h" +#include "driver/include/m2m_types.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#define M2M_ATE_MAX_NUM_OF_RATES (20) +/*!< Maximum number of all rates (b,g and n) + */ +#define M2M_ATE_MAX_FRAME_LENGTH (1024) +/*!< Maximum number of length for each frame + */ +#define M2M_ATE_MIN_FRAME_LENGTH (1) +/*!< Minimum number of length for each frame + */ + + +#define M2M_ATE_SUCCESS (M2M_SUCCESS) +/*!< No Error and operation has been completed successfully. +*/ +#define M2M_ATE_ERR_VALIDATE (M2M_ERR_FAIL) +/*!< Error in parameters passed to functions. + */ +#define M2M_ATE_ERR_TX_ALREADY_RUNNING (-1) +/*!< This means that TX case is already running and RX or even TX can't start without stopping it first. + */ +#define M2M_ATE_ERR_RX_ALREADY_RUNNING (-2) +/*!< This means that RX case is already running and TX or even RX can't start without stopping it first. + */ +#define M2M_ATE_ERR_UNHANDLED_CASE (-3) +/*!< Invalid case. + */ +#define M2M_ATE_RX_DISABLE_DA 0x0 +#define M2M_ATE_RX_ENABLE_DA 0x1 + +#define M2M_ATE_RX_DISABLE_SA 0x0 +#define M2M_ATE_RX_ENABLE_SA 0x1 + +#define M2M_ATE_DISABLE_SELF_MACADDR 0x0 +#define M2M_ATE_SET_SELF_MACADDR 0x1 +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/*! + *@enum tenuM2mAteFwState + *@brief Enumeration used for change ATE firmware state + */ +typedef enum { + M2M_ATE_FW_STATE_STOP = 0x00, + /*!< State to stop ATE firmware + */ + M2M_ATE_FW_STATE_RUN = 0x01, + /*!< State to run ATE firmware + */ +}tenuM2mAteFwState; + +/*! + *@enum tenuM2mAteTxRates + *@brief Used to get value of rate referenced by this index + */ +typedef enum { + M2M_ATE_TX_RATE_1_Mbps_INDEX = 0x00, + M2M_ATE_TX_RATE_2_Mbps_INDEX = 0x01, + M2M_ATE_TX_RATE_55_Mbps_INDEX = 0x02, + M2M_ATE_TX_RATE_11_Mbps_INDEX = 0x03, + /*!< B-Rates + */ + M2M_ATE_TX_RATE_6_Mbps_INDEX = 0x04, + M2M_ATE_TX_RATE_9_Mbps_INDEX = 0x05, + M2M_ATE_TX_RATE_12_Mbps_INDEX = 0x06, + M2M_ATE_TX_RATE_18_Mbps_INDEX = 0x07, + M2M_ATE_TX_RATE_24_Mbps_INDEX = 0x08, + M2M_ATE_TX_RATE_36_Mbps_INDEX = 0x09, + M2M_ATE_TX_RATE_48_Mbps_INDEX = 0x0A, + M2M_ATE_TX_RATE_54_Mbps_INDEX = 0x0B, + /*!< G-Rates + */ + M2M_ATE_TX_RATE_MCS_0_INDEX = 0x0C, + M2M_ATE_TX_RATE_MCS_1_INDEX = 0x0D, + M2M_ATE_TX_RATE_MCS_2_INDEX = 0x0E, + M2M_ATE_TX_RATE_MCS_3_INDEX = 0x0F, + M2M_ATE_TX_RATE_MCS_4_INDEX = 0x10, + M2M_ATE_TX_RATE_MCS_5_INDEX = 0x11, + M2M_ATE_TX_RATE_MCS_6_INDEX = 0x12, + M2M_ATE_TX_RATE_MCS_7_INDEX = 0x13, + /*!< N-Rates + */ +}tenuM2mAteTxIndexOfRates; + +/*! + *@enum tenuM2mAteTxDutyCycle + *@brief Values of duty cycle + */ +typedef enum { + M2M_ATE_TX_DUTY_1 = 0x01, + M2M_ATE_TX_DUTY_2 = 0x02, + M2M_ATE_TX_DUTY_3 = 0x03, + M2M_ATE_TX_DUTY_4 = 0x04, + M2M_ATE_TX_DUTY_5 = 0x05, + M2M_ATE_TX_DUTY_6 = 0x06, + M2M_ATE_TX_DUTY_7 = 0x07, + M2M_ATE_TX_DUTY_8 = 0x08, + M2M_ATE_TX_DUTY_9 = 0x09, + M2M_ATE_TX_DUTY_10 = 0xA0, +}tenuM2mAteTxDutyCycle; + + +#define M2M_ATE_TX_DUTY_MAX_VALUE M2M_ATE_TX_DUTY_1 +/*!< The maximum value of duty cycle +*/ +#define M2M_ATE_TX_DUTY_MIN_VALUE M2M_ATE_TX_DUTY_10 +/*!< The minimum value of duty cycle +*/ + +/*! + *@enum tenuM2mAteTxDpdControl + *@brief Allowed values for DPD control + */ +typedef enum { + M2M_ATE_TX_DPD_DYNAMIC = 0x00, + M2M_ATE_TX_DPD_BYPASS = 0x01, + M2M_ATE_TX_DPD_ENABLED = 0x02, +}tenuM2mAteTxDpdControl; + +/*! + *@enum tenuM2mAteTxGainSetting + *@brief Options for TX gain selection mode + */ +typedef enum { + M2M_ATE_TX_GAIN_DYNAMIC = 0x00, + M2M_ATE_TX_GAIN_BYPASS = 0x01, + M2M_ATE_TX_GAIN_FCC = 0x02, + M2M_ATE_TX_GAIN_TELEC = 0x03, +}tenuM2mAteTxGainSetting; + +/*! + *@enum tenuM2mAtePMUSetting + *@brief Used to Enable PMU or disable it + */ +typedef enum { + M2M_ATE_PMU_DISBLE = 0x00, + M2M_ATE_PMU_ENABLE = 0x01, +}tenuM2mAtePMUSetting; + +/*! + *@enum tenuM2mAteTxSource + *@brief Used to define if enable PHY continues mode or MAC + */ +typedef enum { + M2M_ATE_TX_SRC_MAC = 0x00, + M2M_ATE_TX_SRC_PHY = 0x01, +}tenuM2mAteTxSource; + +/*! + *@enum tenuM2mAteTxMode + *@brief Used to define type of TX mode either normal or CW(Continuous Wave) TX sequence + */ +typedef enum { + M2M_ATE_TX_MODE_NORM = 0x00, + M2M_ATE_TX_MODE_CW = 0x01, +}tenuM2mAteTxMode; + +/*! + *@enum tenuM2mAteRxPwrMode + *@brief Used to define type of RX mode either high power or low power + */ +typedef enum { + M2M_ATE_RX_PWR_HIGH = 0x00, + M2M_ATE_RX_PWR_LOW = 0x01, +}tenuM2mAteRxPwrMode; + +/*! + *@enum tenuM2mAteChannels + *@brief Available channels for TX and RX + */ +typedef enum { + M2M_ATE_CHANNEL_1 = 0x01, + M2M_ATE_CHANNEL_2 = 0x02, + M2M_ATE_CHANNEL_3 = 0x03, + M2M_ATE_CHANNEL_4 = 0x04, + M2M_ATE_CHANNEL_5 = 0x05, + M2M_ATE_CHANNEL_6 = 0x06, + M2M_ATE_CHANNEL_7 = 0x07, + M2M_ATE_CHANNEL_8 = 0x08, + M2M_ATE_CHANNEL_9 = 0x09, + M2M_ATE_CHANNEL_10 = 0x0A, + M2M_ATE_CHANNEL_11 = 0x0B, + M2M_ATE_CHANNEL_12 = 0x0C, + M2M_ATE_CHANNEL_13 = 0x0D, + M2M_ATE_CHANNEL_14 = 0x0E, +}tenuM2mAteChannels; + +/*! + *@struct tstrM2mAteRxStatus + *@brief Used to save statistics of RX case + */ +typedef struct { + uint32 num_rx_pkts; + /*!< Number of total RX packet + */ + uint32 num_err_pkts; + /*!< Number of RX failed packets + */ + uint32 num_good_pkts; + /*!< Number of RX packets actually received + */ +} tstrM2mAteRxStatus; + +/*! + *@struct tstrM2mAteRxStatus + *@brief Used to save statistics of RX case + */ +typedef struct { + uint8 u8RxPwrMode; + /*!< RX power mode review tenuM2mAteRxPwrMode + */ +} tstrM2mAteInit; + +/*! + *@struct tstrM2mAteTx + *@brief Used as data source in case of enabling TX test case + */ +typedef struct { + uint32 num_frames; + /*!< Number of frames to be sent where maximum number allowed is 4294967295 ul, and ZERO means infinite number of frames + */ + uint32 data_rate; + /*!< Rate to sent packets over to select rate use value of \ref tenuM2mAteTxIndexOfRates and pass it to \ref m2m_ate_get_tx_rate + */ + uint8 channel_num; + /*!< Channel number \ref tenuM2mAteChannels + */ + uint8 duty_cycle; + /*!< Duty cycle value between from 1 to 10, where maximum = 1, minimum = 10 \ref tenuM2mAteTxDutyCycle + */ + uint16 frame_len; + /*!< Use \ref M2M_ATE_MAX_FRAME_LENGTH (1024) as the maximum value while \ref M2M_ATE_MIN_FRAME_LENGTH (1) is the minimum value + */ + uint8 tx_gain_sel; + /*!< TX gain mode selection value \ref tenuM2mAteTxGainSetting + */ + uint8 dpd_ctrl; + /*!< DPD mode value\ref tenuM2mAteTxDpdControl + */ + uint8 use_pmu; + /*!< This is 0 if PMU is not used otherwise it must be be 1 \ref tenuM2mAtePMUSetting + */ + uint8 phy_burst_tx; + /*!< Source of Burst TX either PHY or MAC\ref tenuM2mAteTxSource + */ + uint8 cw_tx; + /*!< Mode of Burst TX either normal TX sequence or CW(Continuous Wave) TX sequence \ref tenuM2mAteTxMode + */ + uint32 xo_offset_x1000; + /*!< Signed XO offset value in PPM (Part Per Million) multiplied by 1000. + */ + uint8 use_efuse_xo_offset; + /*!< Set to 0 to use the XO offset provided in xo_offset_x1000. Set to 1 to use XO offset programmed on WINC efuse. + */ + uint8 peer_mac_addr[6]; + /*!< Set peer address to send directed frames to a certain address. + */ +} tstrM2mAteTx; + +/*! + *@struct tstrM2mAteRx + *@brief Used as data source in case of enabling RX test case + */ +typedef struct { + uint8 channel_num; + /*!< Channel number \ref tenuM2mAteChannels + */ + uint8 use_pmu; + /*!< This is 0 if PMU is not used otherwise it must be be 1 \ref tenuM2mAtePMUSetting + */ + uint32 xo_offset_x1000; + /*!< Signed XO offset value in PPM (Part Per Million) multiplied by 1000. + */ + uint8 use_efuse_xo_offset; + /*!< Set to 0 to use the XO offset provided in xo_offset_x1000. Set to 1 to use XO offset programmed on WINC efuse. + */ + uint8 self_mac_addr[6]; + /*!< Set to the self mac address required to be overriden. + */ + uint8 peer_mac_addr[6]; + /*!< Set to the source mac address expected to filter frames from. + */ + uint8 mac_filter_en_da; + /*!< Flag set to enable or disable reception with destination address as a filter. + */ + uint8 mac_filter_en_sa; + /*!< Flag set to enable or disable reception with source address as a filter. + */ + uint8 override_self_mac_addr; + /*!< Flag set to enable or disable self mac address feature. + */ +} tstrM2mAteRx; + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#ifdef __cplusplus + extern "C" { +#endif + +/*! +@fn \ + sint8 m2m_ate_init(void); + +@brief + This function used to download ATE firmware from flash and start it + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_init(void); + + +/*! +@fn \ + sint8 m2m_ate_init(tstrM2mAteInit *pstrInit); + +@brief + This function used to download ATE firmware from flash and start it + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_init_param(tstrM2mAteInit *pstrInit); + +/*! +@fn \ + sint8 m2m_ate_deinit(void); + +@brief + De-Initialization of ATE firmware mode + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_deinit(void); + +/*! +@fn \ + sint8 m2m_ate_set_fw_state(uint8); + +@brief + This function used to change ATE firmware status from running to stopped or vice versa. + +@param [in] u8State + Required state of ATE firmware, one of \ref tenuM2mAteFwState enumeration values. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init +*/ +sint8 m2m_ate_set_fw_state(uint8); + +/*! +@fn \ + sint8 m2m_ate_get_fw_state(uint8); + +@brief + This function used to return status of ATE firmware. + +@return + The function SHALL return status of ATE firmware, one of \ref tenuM2mAteFwState enumeration values. +\sa + m2m_ate_init, m2m_ate_set_fw_state +*/ +sint8 m2m_ate_get_fw_state(void); + +/*! +@fn \ + uint32 m2m_ate_get_tx_rate(uint8); + +@brief + This function used to return value of TX rate required by application developer. + +@param [in] u8Index + Index of required rate , one of \ref tenuM2mAteTxIndexOfRates enumeration values. +@return + The function SHALL return 0 for in case of failure otherwise selected rate value. +\sa + tenuM2mAteTxIndexOfRates +*/ +uint32 m2m_ate_get_tx_rate(uint8); + +/*! +@fn \ + sint8 m2m_ate_get_tx_status(void); + +@brief + This function used to return status of TX test case either running or stopped. + +@return + The function SHALL return status of ATE firmware, 1 if TX is running otherwise 0. +\sa + m2m_ate_start_tx, m2m_ate_stop_tx +*/ +sint8 m2m_ate_get_tx_status(void); + +/*! +@fn \ + sint8 m2m_ate_start_tx(tstrM2mAteTx *) + +@brief + This function used to start TX test case. + +@param [in] strM2mAteTx + Type of \ref tstrM2mAteTx, with the values required to enable TX test case. You must use \ref m2m_ate_init first. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_stop_tx, m2m_ate_get_tx_status +*/ +sint8 m2m_ate_start_tx(tstrM2mAteTx *); + +/*! +@fn \ + sint8 m2m_ate_stop_tx(void) + +@brief + This function used to stop TX test case. + +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_start_tx, m2m_ate_get_tx_status +*/ +sint8 m2m_ate_stop_tx(void); + +/*! +@fn \ + sint8 m2m_ate_get_rx_status(uint8); + +@brief + This function used to return status of RX test case either running or stopped. + +@return + The function SHALL return status of ATE firmware, 1 if RX is running otherwise 0. +\sa + m2m_ate_start_rx, m2m_ate_stop_rx +*/ +sint8 m2m_ate_get_rx_status(void); + +/*! +@fn \ + sint8 m2m_ate_start_rx(tstrM2mAteRx *) + +@brief + This function used to start RX test case. + +@param [in] strM2mAteRx + Type of \ref tstrM2mAteRx, with the values required to enable RX test case. You must use \ref m2m_ate_init first. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_stop_rx, m2m_ate_get_rx_status +*/ +sint8 m2m_ate_start_rx(tstrM2mAteRx *); + +/*! +@fn \ + sint8 m2m_ate_stop_rx(void) + +@brief + This function used to stop RX test case. + +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_start_rx, m2m_ate_get_rx_status +*/ +sint8 m2m_ate_stop_rx(void); + +/*! +@fn \ + sint8 m2m_ate_read_rx_status(tstrM2mAteRxStatus *) + +@brief + This function used to read RX statistics from ATE firmware. + +@param [out] strM2mAteRxStatus + Type of \ref tstrM2mAteRxStatus used to save statistics of RX test case. You must use \ref m2m_ate_start_rx first. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_start_rx +*/ +sint8 m2m_ate_read_rx_status(tstrM2mAteRxStatus *); + +/*! +@fn \ + sint8 m2m_ate_set_dig_gain(double dGaindB) + +@brief + This function is used to set the digital gain + +@param [in] double dGaindB + The digital gain value required to be set. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_set_dig_gain(double dGaindB); + +/*! +@fn \ + sint8 m2m_ate_get_dig_gain(double * dGaindB) + +@brief + This function is used to get the digital gain + +@param [out] double * dGaindB + The retrieved digital gain value obtained from HW registers in dB. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_dig_gain(double * dGaindB); + +/*! +@fn \ + sint8 m2m_ate_get_pa_gain(double *paGaindB) + +@brief + This function is used to get the PA gain + +@param [out] double *paGaindB + The retrieved PA gain value obtained from HW registers in dB. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_pa_gain(double *paGaindB); + +/*! +@fn \ + sint8 m2m_ate_get_ppa_gain(double * ppaGaindB) + +@brief + This function is used to get the PPA gain + +@param [out] uint32 * ppaGaindB + The retrieved PPA gain value obtained from HW registers in dB. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_ppa_gain(double * ppaGaindB); + +/*! +@fn \ + sint8 m2m_ate_get_tot_gain(double * totGaindB) + +@brief + This function is used to calculate the total gain + +@param [out] double * totGaindB + The retrieved total gain value obtained from calculations made based on the digital gain, PA and PPA gain values. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_tot_gain(double * totGaindB); + + +#ifdef __cplusplus +} +#endif + +#endif /* _M2M_CONFIG_MODE_H_ */ + +#endif //_M2M_ATE_FW_ \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/driver/include/m2m_crypto.h b/ext/drivers/atmel/winc1500/driver/include/m2m_crypto.h new file mode 100755 index 0000000000000..c03b3af1b5c79 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/include/m2m_crypto.h @@ -0,0 +1,245 @@ +/** + * + * \file + * + * \brief WINC Crypto Application Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef __M2M_CRYPTO_H__ +#define __M2M_CRYPTO_H__ + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +#include "common/include/nm_common.h" +#include "driver/include/m2m_types.h" +#include "driver/source/m2m_hif.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#define M2M_MAX_RSA_LEN (256) +#define M2M_SHA256_DIGEST_LEN 32 +#define M2M_SHA256_MAX_DATA (M2M_BUFFER_MAX_SIZE - M2M_SHA256_CONTEXT_BUFF_LEN - M2M_HIF_HDR_OFFSET) +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*! +@struct \ + tstrM2mSha256Ctxt + +@brief + SHA256 context data +*/ +typedef struct sha256ctxt{ + uint32 au32Sha256CtxtBuff[M2M_SHA256_CONTEXT_BUFF_LEN/sizeof(uint32)]; +} tstrM2mSha256Ctxt; + + + +/*! +@enum \ + tenuRsaSignStatus + +@brief + RSA Signature status: pass or fail. +*/ +typedef enum{ + M2M_RSA_SIGN_OK, + M2M_RSA_SIGN_FAIL +} tenuRsaSignStatus; + +/*! +@typedef \ + tpfAppCryproCb + +@brief +@param [in] u8MsgType + +@param [in] pvMsg + A pointer to a buffer containing the notification parameters (if any). It should be + Casted to the correct data type corresponding to the notification type. + + +*/ +typedef void (*tpfAppCryproCb) (uint8 u8MsgType,void * pvResp, void * pvMsg); + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +#ifdef __cplusplus + extern "C" { +#endif +/*! +@fn \ + sint8 m2m_crypto_init(); + +@brief crypto initialization + +@param[in] pfAppCryproCb + +*/ +sint8 m2m_crypto_init(tpfAppCryproCb pfAppCryproCb); +/*! +@fn \ + sint8 m2m_sha256_hash_init(tstrM2mSha256Ctxt *psha256Ctxt); + +@brief SHA256 hash initialization + +@param[in] psha256Ctxt + Pointer to a sha256 context allocated by the caller. +*/ +sint8 m2m_crypto_sha256_hash_init(tstrM2mSha256Ctxt *psha256Ctxt); + + +/*! +@fn \ + sint8 m2m_sha256_hash_update(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Data, uint16 u16DataLength); + +@brief SHA256 hash update + +@param [in] psha256Ctxt + Pointer to the sha256 context. + +@param [in] pu8Data + Buffer holding the data submitted to the hash. + +@param [in] u16DataLength + Size of the data bufefr in bytes. +*/ +sint8 m2m_crypto_sha256_hash_update(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Data, uint16 u16DataLength); + + +/*! +@fn \ + sint8 m2m_sha256_hash_finish(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Sha256Digest); + +@brief SHA256 hash finalization + +@param[in] psha256Ctxt + Pointer to a sha256 context allocated by the caller. + +@param [in] pu8Sha256Digest + Buffer allocated by the caller which will hold the resultant SHA256 Digest. It must be allocated no less than M2M_SHA256_DIGEST_LEN. +*/ +sint8 m2m_crypto_sha256_hash_finish(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Sha256Digest); + + + + +/*! +@fn \ + sint8 m2m_rsa_sign_verify(uint8 *pu8N, uint16 u16NSize, uint8 *pu8E, uint16 u16ESize, uint8 *pu8SignedMsgHash, \ + uint16 u16HashLength, uint8 *pu8RsaSignature); + +@brief RSA Signature Verification + + The function shall request the RSA Signature verification from the WINC Firmware for the given message. The signed message shall be + compressed to the corresponding hash algorithm before calling this function. + The hash type is identified by the given hash length. For example, if the hash length is 32 bytes, then it is SHA256. + +@param[in] pu8N + RSA Key modulus n. + +@param[in] u16NSize + Size of the RSA modulus n in bytes. + +@param[in] pu8E + RSA public exponent. + +@param[in] u16ESize + Size of the RSA public exponent in bytes. + +@param[in] pu8SignedMsgHash + The hash digest of the signed message. + +@param[in] u16HashLength + The length of the hash digest. + +@param[out] pu8RsaSignature + Signature value to be verified. +*/ +sint8 m2m_crypto_rsa_sign_verify(uint8 *pu8N, uint16 u16NSize, uint8 *pu8E, uint16 u16ESize, uint8 *pu8SignedMsgHash, + uint16 u16HashLength, uint8 *pu8RsaSignature); + + +/*! +@fn \ + sint8 m2m_rsa_sign_gen(uint8 *pu8N, uint16 u16NSize, uint8 *pu8d, uint16 u16dSize, uint8 *pu8SignedMsgHash, \ + uint16 u16HashLength, uint8 *pu8RsaSignature); + +@brief RSA Signature Generation + + The function shall request the RSA Signature generation from the WINC Firmware for the given message. The signed message shall be + compressed to the corresponding hash algorithm before calling this function. + The hash type is identified by the given hash length. For example, if the hash length is 32 bytes, then it is SHA256. + +@param[in] pu8N + RSA Key modulus n. + +@param[in] u16NSize + Size of the RSA modulus n in bytes. + +@param[in] pu8d + RSA private exponent. + +@param[in] u16dSize + Size of the RSA private exponent in bytes. + +@param[in] pu8SignedMsgHash + The hash digest of the signed message. + +@param[in] u16HashLength + The length of the hash digest. + +@param[out] pu8RsaSignature + Pointer to a user buffer allocated by teh caller shall hold the generated signature. +*/ +sint8 m2m_crypto_rsa_sign_gen(uint8 *pu8N, uint16 u16NSize, uint8 *pu8d, uint16 u16dSize, uint8 *pu8SignedMsgHash, + uint16 u16HashLength, uint8 *pu8RsaSignature); +#ifdef __cplusplus +} +#endif + + +#endif /* __M2M_CRYPTO_H__ */ \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/driver/include/m2m_ota.h b/ext/drivers/atmel/winc1500/driver/include/m2m_ota.h new file mode 100755 index 0000000000000..80c5eaf6b2bc1 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/include/m2m_ota.h @@ -0,0 +1,342 @@ +/** + * + * \file + * + * \brief WINC OTA Upgrade API Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef __M2M_OTA_H__ +#define __M2M_OTA_H__ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "common/include/nm_common.h" +#include "driver/include/m2m_types.h" +#include "driver/source/nmdrv.h" +/**@addtogroup WlanEnums Enumerations and Typedefs + * @ingroup m2m_wifi + */ + /* @{ */ + + +/*! +@typedef void (*tpfOtaNotifCb) (tstrOtaUpdateInfo *); + +@brief A callback to get notification about an potential OTA update. + +@param[in] pstrOtaUpdateInfo A structure to provide notification payload. + +@sa + tstrOtaUpdateInfo +@warning + The notification is not supported (Not implemented yet) + +*/ +typedef void (*tpfOtaNotifCb) (tstrOtaUpdateInfo * pstrOtaUpdateInfo); + + +/*! +@typedef void (*tpfOtaUpdateCb) (uint8 u8OtaUpdateStatusType ,uint8 u8OtaUpdateStatus); + +@brief + A callback to get OTA status update, the callback provide the status type and its status the OTA callback provides the download status, + the switch to the downloaded firmware status and roll-back status. + +@param[in] u8OtaUpdateStatusType Possible values are listed in tenuOtaUpdateStatusType. Possible types are: +- [DL_STATUS](@ref DL_STATUS) +- [SW_STATUS](@ref SW_STATUS) +- [RB_STATUS](@ref RB_STATUS) + +@param[in] u8OtaUpdateStatus Possible values are listed in tenuOtaUpdateStatus. + +@see + tenuOtaUpdateStatusType + tenuOtaUpdateStatus + */ +typedef void (*tpfOtaUpdateCb) (uint8 u8OtaUpdateStatusType ,uint8 u8OtaUpdateStatus); + /**@}*/ +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#ifdef __cplusplus + extern "C" { +#endif + +/** @defgroup OtaInitFn m2m_ota_init + * @ingroup WLANAPI +* Synchronous initialization function for the OTA layer by registering the update callback. +* The notification callback is not supported at the current version. Calling this API is a +* MUST for all the OTA API's. + + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_init(tpfOtaUpdateCb pfOtaUpdateCb,tpfOtaNotifCb pfOtaNotifCb) + +@param [in] pfOtaUpdateCb + OTA Update callback function + +@param [in] pfOtaNotifCb + OTA notify callback function + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_init(tpfOtaUpdateCb pfOtaUpdateCb,tpfOtaNotifCb pfOtaNotifCb); + /**@}*/ + + /** @defgroup OtaNotifStFn m2m_ota_notif_set_url + * @ingroup WLANAPI + * Set the OTA notification server URL, the functions need to be called before any check for update + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_notif_set_url(uint8 * u8Url); + +@param [in] u8Url + Set the OTA notification server URL, the functions need to be called before any check for update. +@warning + Calling m2m_ota_init is required + Notification Server is not supported in the current version (function is not implemented) +@see + m2m_ota_init +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_notif_set_url(uint8 * u8Url); + /**@}*/ + /** @defgroup OtaNotifCheckFn m2m_ota_notif_check_for_update + * @ingroup WLANAPI + * Synchronous function to check for the OTA update using the Notification Server + * URL. Function is not implemented (not supported at the current version) + * + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_notif_check_for_update(void); + +@warning + Function is not implemented (not supported at the current version) + +@sa + m2m_ota_init + m2m_ota_notif_set_url +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_notif_check_for_update(void); + /**@}*/ + /** @defgroup OtaSched m2m_ota_notif_sched +* @ingroup WLANAPI +* Schedule OTA notification Server check for update request after specific number of days +*/ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_notif_sched(uint32 u32Period); + + +@param [in] u32Period + Period in days + +@sa + m2m_ota_init + m2m_ota_notif_check_for_update + m2m_ota_notif_set_url +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_notif_sched(uint32 u32Period); + /**@}*/ +/** @defgroup OtaStartUpdatefn m2m_ota_start_update +* @ingroup WLANAPI +* Request OTA start update using the downloaded URL, the OTA module will download the OTA image and ensure integrity of the image, +* and update the validity of the image in control structure. Switching to that image requires calling @ref m2m_ota_switch_firmware API. +* As a prerequisite @ref m2m_ota_init should be called before using @ref m2m_ota_start(). +*/ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_start_update(uint8 * u8DownloadUrl); + +@param [in] u8DownloadUrl + The download firmware URL, you get it from device info according to the application server + +@warning + Calling this API does not guarantee OTA WINC image update, It depends on the connection with the download server and the validity of the image. + If the API response is failure this may invalidate the roll-back image if it was previously valid, since the WINC does not have any internal memory + except the flash roll-back image location to validate the downloaded image from + +@see + m2m_ota_init + tpfOtaUpdateCb + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The example shows an example of how the OTA image update is carried out. +@code +static void OtaUpdateCb(uint8 u8OtaUpdateStatusType ,uint8 u8OtaUpdateStatus) +{ + if(u8OtaUpdateStatusType == DL_STATUS) { + if(u8OtaUpdateStatus == OTA_STATUS_SUCSESS) { + //switch to the upgraded firmware + m2m_ota_switch_firmware(); + } + } + else if(u8OtaUpdateStatusType == SW_STATUS) { + if(u8OtaUpdateStatus == OTA_STATUS_SUCSESS) { + M2M_INFO("Now OTA successfully done"); + //start the host SW upgrade then system reset is required (Reinitialize the driver) + } + } +} +void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) +{ + case M2M_WIFI_REQ_DHCP_CONF: + { + //after successfully connection, start the over air upgrade + m2m_ota_start_update(OTA_URL); + } + break; + default: + break; +} +int main (void) +{ + tstrWifiInitParam param; + tstr1xAuthCredentials gstrCred1x = AUTH_CREDENTIALS; + nm_bsp_init(); + + m2m_memset((uint8*)¶m, 0, sizeof(param)); + param.pfAppWifiCb = wifi_event_cb; + + //Initialize the WINC Driver + ret = m2m_wifi_init(¶m); + if (M2M_SUCCESS != ret) + { + M2M_ERR("Driver Init Failed <%d>\n",ret); + while(1); + } + //Initialize the OTA module + m2m_ota_init(OtaUpdateCb,NULL); + //connect to AP that provide connection to the OTA server + m2m_wifi_default_connect(); + + while(1) + { + + //Handle the app state machine plus the WINC event handler + while(m2m_wifi_handle_events(NULL) != M2M_SUCCESS) { + + } + + } +} +@endcode + +*/ +NMI_API sint8 m2m_ota_start_update(uint8 * u8DownloadUrl); + /**@}*/ +/** @defgroup OtaRollbackfn m2m_ota_rollback +* @ingroup WLANAPI + Request OTA Roll-back to the old (other) WINC image, the WINC firmware will check the validation of the Roll-back image + and switch to it if it is valid. + If the API response is success, system restart is required (re-initialize the driver with hardware rest) update the host driver version may + be required if it is did not match the minimum version supported by the WINC firmware. + +*/ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_rollback(void); + +@sa + m2m_ota_init + m2m_ota_start_update + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_rollback(void); + /**@}*/ + /**@}*/ +/** @defgroup OtaSwitchFirmware m2m_ota_switch_firmware +* @ingroup WLANAPI +* Switch to the upgraded Firmware, that API will update the control structure working image to the upgraded image + take effect will be on the next system restart +*/ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_ota_switch_firmware(void); + +@warning + It is important to note that if the API succeeds, system restart is required (re-initializing the driver with hardware reset) updating the host driver version may be required + if it does not match the minimum driver version supported by the WINC's firmware. +@sa + m2m_ota_init + m2m_ota_start_update + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_switch_firmware(void); +/*! +@fn \ + NMI_API sint8 m2m_ota_get_firmware_version(void); + +@brief + Get the OTA Firmware version. + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_get_firmware_version(tstrM2mRev *pstrRev); + /**@}*/ +NMI_API sint8 m2m_ota_test(void); + +#ifdef __cplusplus +} +#endif +#endif /* __M2M_OTA_H__ */ diff --git a/ext/drivers/atmel/winc1500/driver/include/m2m_periph.h b/ext/drivers/atmel/winc1500/driver/include/m2m_periph.h new file mode 100755 index 0000000000000..1012882f0211b --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/include/m2m_periph.h @@ -0,0 +1,411 @@ +/** + * + * \file + * + * \brief WINC Peripherals Application Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _M2M_PERIPH_H_ +#define _M2M_PERIPH_H_ + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +#include "common/include/nm_common.h" +#include "driver/include/m2m_types.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*! +@struct \ + tstrPerphInitParam + +@brief + Peripheral module initialization parameters. +*/ +typedef struct { + void * arg; +} tstrPerphInitParam; + + +/*! +@enum \ + tenuGpioNum + +@brief + A list of GPIO numbers configurable through the m2m_periph module. +*/ +typedef enum { + M2M_PERIPH_GPIO3, /*!< GPIO15 pad */ + M2M_PERIPH_GPIO4, /*!< GPIO16 pad */ + M2M_PERIPH_GPIO5, /*!< GPIO18 pad */ + M2M_PERIPH_GPIO6, /*!< GPIO18 pad */ + M2M_PERIPH_GPIO15, /*!< GPIO15 pad */ + M2M_PERIPH_GPIO16, /*!< GPIO16 pad */ + M2M_PERIPH_GPIO18, /*!< GPIO18 pad */ + M2M_PERIPH_GPIO_MAX +} tenuGpioNum; + + +/*! +@enum \ + tenuI2cMasterSclMuxOpt + +@brief + Allowed pin multiplexing options for I2C master SCL signal. +*/ +typedef enum { + M2M_PERIPH_I2C_MASTER_SCL_MUX_OPT_HOST_WAKEUP, /*!< I2C master SCL is avaiable on HOST_WAKEUP. */ + M2M_PERIPH_I2C_MASTER_SCL_MUX_OPT_SD_DAT3, /*!< I2C master SCL is avaiable on SD_DAT3 (GPIO 7). */ + M2M_PERIPH_I2C_MASTER_SCL_MUX_OPT_GPIO13, /*!< I2C master SCL is avaiable on GPIO 13. */ + M2M_PERIPH_I2C_MASTER_SCL_MUX_OPT_GPIO4, /*!< I2C master SCL is avaiable on GPIO 4.*/ + M2M_PERIPH_I2C_MASTER_SCL_MUX_OPT_I2C_SCL, /*!< I2C master SCL is avaiable on I2C slave SCL. */ + M2M_PERIPH_I2C_MASTER_SCL_MUX_OPT_NUM +} tenuI2cMasterSclMuxOpt; + +/*! +@enum \ + tenuI2cMasterSdaMuxOpt + +@brief + Allowed pin multiplexing options for I2C master SDA signal. +*/ +typedef enum { + M2M_PERIPH_I2C_MASTER_SDA_MUX_OPT_RTC_CLK , /*!< I2C master SDA is avaiable on RTC_CLK. */ + M2M_PERIPH_I2C_MASTER_SDA_MUX_OPT_SD_CLK, /*!< I2C master SDA is avaiable on SD_CLK (GPIO 8). */ + M2M_PERIPH_I2C_MASTER_SDA_MUX_OPT_GPIO14, /*!< I2C master SDA is avaiable on GPIO 14. */ + M2M_PERIPH_I2C_MASTER_SDA_MUX_OPT_GPIO6, /*!< I2C master SDA is avaiable on GPIO 6.*/ + M2M_PERIPH_I2C_MASTER_SDA_MUX_OPT_I2C_SDA, /*!< I2C master SDA is avaiable on I2C slave SDA. */ + M2M_PERIPH_I2C_MASTER_SDA_MUX_OPT_NUM +} tenuI2cMasterSdaMuxOpt; + + +/*! +@struct \ + tstrI2cMasterInitParam + +@brief + I2C master configuration parameters. +@sa + tenuI2cMasterSclMuxOpt + tenuI2cMasterSdaMuxOpt +*/ +typedef struct { + uint8 enuSclMuxOpt; /*!< SCL multiplexing option. Allowed value are defined in tenuI2cMasterSclMuxOpt */ + uint8 enuSdaMuxOpt; /*!< SDA multiplexing option. Allowed value are defined in tenuI2cMasterSdaMuxOpt */ + uint8 u8ClkSpeedKHz; /*!< I2C master clock speed in KHz. */ +} tstrI2cMasterInitParam; + +/*! +@enum \ + tenuI2cMasterFlags + +@brief + Bitwise-ORed flags for use in m2m_periph_i2c_master_write and m2m_periph_i2c_master_read +@sa + m2m_periph_i2c_master_write + m2m_periph_i2c_master_read +*/ +typedef enum { + I2C_MASTER_NO_FLAGS = 0x00, + /*!< No flags. */ + I2C_MASTER_NO_STOP = 0x01, + /*!< No stop bit after this transaction. Useful for scattered buffer read/write operations. */ + I2C_MASTER_NO_START = 0x02, + /*!< No start bit at the beginning of this transaction. Useful for scattered buffer read/write operations.*/ +} tenuI2cMasterFlags; + +/*! +@enum \ + tenuPullupMask + +@brief + Bitwise-ORed flags for use in m2m_perph_pullup_ctrl. +@sa + m2m_periph_pullup_ctrl + +*/ +typedef enum { + M2M_PERIPH_PULLUP_DIS_HOST_WAKEUP = (1ul << 0), + M2M_PERIPH_PULLUP_DIS_RTC_CLK = (1ul << 1), + M2M_PERIPH_PULLUP_DIS_IRQN = (1ul << 2), + M2M_PERIPH_PULLUP_DIS_GPIO_3 = (1ul << 3), + M2M_PERIPH_PULLUP_DIS_GPIO_4 = (1ul << 4), + M2M_PERIPH_PULLUP_DIS_GPIO_5 = (1ul << 5), + M2M_PERIPH_PULLUP_DIS_SD_DAT3 = (1ul << 6), + M2M_PERIPH_PULLUP_DIS_SD_DAT2_SPI_RXD = (1ul << 7), + M2M_PERIPH_PULLUP_DIS_SD_DAT1_SPI_SSN = (1ul << 9), + M2M_PERIPH_PULLUP_DIS_SD_CMD_SPI_SCK = (1ul << 10), + M2M_PERIPH_PULLUP_DIS_SD_DAT0_SPI_TXD = (1ul << 11), + M2M_PERIPH_PULLUP_DIS_GPIO_6 = (1ul << 12), + M2M_PERIPH_PULLUP_DIS_SD_CLK = (1ul << 13), + M2M_PERIPH_PULLUP_DIS_I2C_SCL = (1ul << 14), + M2M_PERIPH_PULLUP_DIS_I2C_SDA = (1ul << 15), + M2M_PERIPH_PULLUP_DIS_GPIO_11 = (1ul << 16), + M2M_PERIPH_PULLUP_DIS_GPIO_12 = (1ul << 17), + M2M_PERIPH_PULLUP_DIS_GPIO_13 = (1ul << 18), + M2M_PERIPH_PULLUP_DIS_GPIO_14 = (1ul << 19), + M2M_PERIPH_PULLUP_DIS_GPIO_15 = (1ul << 20), + M2M_PERIPH_PULLUP_DIS_GPIO_16 = (1ul << 21), + M2M_PERIPH_PULLUP_DIS_GPIO_17 = (1ul << 22), + M2M_PERIPH_PULLUP_DIS_GPIO_18 = (1ul << 23), + M2M_PERIPH_PULLUP_DIS_GPIO_19 = (1ul << 24), + M2M_PERIPH_PULLUP_DIS_GPIO_20 = (1ul << 25), + M2M_PERIPH_PULLUP_DIS_GPIO_21 = (1ul << 26), + M2M_PERIPH_PULLUP_DIS_GPIO_22 = (1ul << 27), + M2M_PERIPH_PULLUP_DIS_GPIO_23 = (1ul << 28), + M2M_PERIPH_PULLUP_DIS_GPIO_24 = (1ul << 29), +} tenuPullupMask; + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +#ifdef __cplusplus + extern "C" { +#endif + +/*! +@fn \ + NMI_API sint8 m2m_periph_init(tstrPerphInitParam * param); + +@brief + Initialize the NMC1500 peripheral driver module. + +@param [in] param + Peripheral module initialization structure. See members of tstrPerphInitParam. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tstrPerphInitParam +*/ +NMI_API sint8 m2m_periph_init(tstrPerphInitParam * param); + +/*! +@fn \ + NMI_API sint8 m2m_periph_gpio_set_dir(uint8 u8GpioNum, uint8 u8GpioDir); + +@brief + Configure a specific NMC1500 pad as a GPIO and sets its direction (input or output). + +@param [in] u8GpioNum + GPIO number. Allowed values are defined in tenuGpioNum. + +@param [in] u8GpioDir + GPIO direction: Zero = input. Non-zero = output. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuGpioNum +*/ +NMI_API sint8 m2m_periph_gpio_set_dir(uint8 u8GpioNum, uint8 u8GpioDir); + +/*! +@fn \ + NMI_API sint8 m2m_periph_gpio_set_val(uint8 u8GpioNum, uint8 u8GpioVal); + +@brief + Set an NMC1500 GPIO output level high or low. + +@param [in] u8GpioNum + GPIO number. Allowed values are defined in tenuGpioNum. + +@param [in] u8GpioVal + GPIO output value. Zero = low, non-zero = high. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuGpioNum +*/ +NMI_API sint8 m2m_periph_gpio_set_val(uint8 u8GpioNum, uint8 u8GpioVal); + +/*! +@fn \ + NMI_API sint8 m2m_periph_gpio_get_val(uint8 u8GpioNum, uint8 * pu8GpioVal); + +@brief + Read an NMC1500 GPIO input level. + +@param [in] u8GpioNum + GPIO number. Allowed values are defined in tenuGpioNum. + +@param [out] pu8GpioVal + GPIO input value. Zero = low, non-zero = high. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuGpioNum +*/ +NMI_API sint8 m2m_periph_gpio_get_val(uint8 u8GpioNum, uint8 * pu8GpioVal); + +/*! +@fn \ + NMI_API sint8 m2m_periph_gpio_pullup_ctrl(uint8 u8GpioNum, uint8 u8PullupEn); + +@brief + Set an NMC1500 GPIO pullup resisitor enable or disable. + +@param [in] u8GpioNum + GPIO number. Allowed values are defined in tenuGpioNum. + +@param [in] u8PullupEn + Zero: pullup disabled. Non-zero: pullup enabled. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuGpioNum +*/ +NMI_API sint8 m2m_periph_gpio_pullup_ctrl(uint8 u8GpioNum, uint8 u8PullupEn); + +/*! +@fn \ + NMI_API sint8 m2m_periph_i2c_master_init(tstrI2cMasterInitParam * param); + +@brief + Initialize and configure the NMC1500 I2C master peripheral. + +@param [in] param + I2C master initialization structure. See members of tstrI2cMasterInitParam. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tstrI2cMasterInitParam +*/ +NMI_API sint8 m2m_periph_i2c_master_init(tstrI2cMasterInitParam * param); + +/*! +@fn \ + NMI_API sint8 m2m_periph_i2c_master_write(uint8 u8SlaveAddr, uint8 * pu8Buf, uint16 u16BufLen, uint8 flags); + +@brief + Write a stream of bytes to the I2C slave device. + +@param [in] u8SlaveAddr + 7-bit I2C slave address. +@param [in] pu8Buf + A pointer to an input buffer which contains a stream of bytes. +@param [in] u16BufLen + Input buffer length in bytes. +@param [in] flags + Write operation bitwise-ORed flags. See tenuI2cMasterFlags. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuI2cMasterFlags +*/ +NMI_API sint8 m2m_periph_i2c_master_write(uint8 u8SlaveAddr, uint8 * pu8Buf, uint16 u16BufLen, uint8 flags); + + +/*! +@fn \ + NMI_API sint8 m2m_periph_i2c_master_read(uint8 u8SlaveAddr, uint8 * pu8Buf, uint16 u16BufLen, uint16 * pu16ReadLen, uint8 flags); + +@brief + Write a stream of bytes to the I2C slave device. + +@param [in] u8SlaveAddr + 7-bit I2C slave address. +@param [out] pu8Buf + A pointer to an output buffer in which a stream of bytes are received. +@param [in] u16BufLen + Max output buffer length in bytes. +@param [out] pu16ReadLen + Actual number of bytes received. +@param [in] flags + Write operation bitwise-ORed flags. See tenuI2cMasterFlags. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuI2cMasterFlags +*/ +NMI_API sint8 m2m_periph_i2c_master_read(uint8 u8SlaveAddr, uint8 * pu8Buf, uint16 u16BufLen, uint16 * pu16ReadLen, uint8 flags); + + +/*! +@fn \ + NMI_API sint8 m2m_periph_pullup_ctrl(uint32 pinmask, uint8 enable); + +@brief + Control the programmable pull-up resistor on the chip pads . + + +@param [in] pinmask + Write operation bitwise-ORed mask for which pads to control. Allowed values are defined in tenuPullupMask. + +@param [in] enable + Set to 0 to disable pull-up resistor. Non-zero will enable the pull-up. + +@return + The function SHALL return 0 for success and a negative value otherwise. + +@sa + tenuPullupMask +*/ +NMI_API sint8 m2m_periph_pullup_ctrl(uint32 pinmask, uint8 enable); + +#ifdef __cplusplus +} +#endif + + +#endif /* _M2M_PERIPH_H_ */ \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/driver/include/m2m_types.h b/ext/drivers/atmel/winc1500/driver/include/m2m_types.h new file mode 100755 index 0000000000000..a911090658b17 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/include/m2m_types.h @@ -0,0 +1,2123 @@ +/** + * + * \file + * + * \brief WINC Application Interface Internal Types. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef __M2M_WIFI_TYPES_H__ +#define __M2M_WIFI_TYPES_H__ + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#ifndef _BOOT_ +#ifndef _FIRMWARE_ +#include "common/include/nm_types.h" +#include "common/include/nm_common.h" +#else +#include "m2m_common.h" +#endif +#endif + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/**@defgroup WlanDefines Defines + * @ingroup m2m_wifi + */ +/**@{*/ +#define M2M_MAJOR_SHIFT (8) +#define M2M_MINOR_SHIFT (4) +#define M2M_PATCH_SHIFT (0) + +#define M2M_DRV_VERSION_SHIFT (16) +#define M2M_FW_VERSION_SHIFT (0) + +#define M2M_GET_MAJOR(ver_info_hword) ((uint8)((ver_info_hword) >> M2M_MAJOR_SHIFT) & 0xff) +#define M2M_GET_MINOR(ver_info_hword) ((uint8)((ver_info_hword) >> M2M_MINOR_SHIFT) & 0x0f) +#define M2M_GET_PATCH(ver_info_hword) ((uint8)((ver_info_hword) >> M2M_PATCH_SHIFT) & 0x0f) + +#define M2M_GET_FW_VER(ver_info_word) ((uint16) ((ver_info_word) >> M2M_FW_VERSION_SHIFT)) +#define M2M_GET_DRV_VER(ver_info_word) ((uint16) ((ver_info_word) >> M2M_DRV_VERSION_SHIFT)) + +#define M2M_GET_DRV_MAJOR(ver_info_word) M2M_GET_MAJOR(M2M_GET_DRV_VER(ver_info_word)) +#define M2M_GET_DRV_MINOR(ver_info_word) M2M_GET_MINOR(M2M_GET_DRV_VER(ver_info_word)) +#define M2M_GET_DRV_PATCH(ver_info_word) M2M_GET_PATCH(M2M_GET_DRV_VER(ver_info_word)) + +#define M2M_GET_FW_MAJOR(ver_info_word) M2M_GET_MAJOR(M2M_GET_FW_VER(ver_info_word)) +#define M2M_GET_FW_MINOR(ver_info_word) M2M_GET_MINOR(M2M_GET_FW_VER(ver_info_word)) +#define M2M_GET_FW_PATCH(ver_info_word) M2M_GET_PATCH(M2M_GET_FW_VER(ver_info_word)) + +#define M2M_MAKE_VERSION(major, minor, patch) ( \ + ((uint16)((major) & 0xff) << M2M_MAJOR_SHIFT) | \ + ((uint16)((minor) & 0x0f) << M2M_MINOR_SHIFT) | \ + ((uint16)((patch) & 0x0f) << M2M_PATCH_SHIFT)) + +#define M2M_MAKE_VERSION_INFO(fw_major, fw_minor, fw_patch, drv_major, drv_minor, drv_patch) \ + ( \ + ( ((uint32)M2M_MAKE_VERSION((fw_major), (fw_minor), (fw_patch))) << M2M_FW_VERSION_SHIFT) | \ + ( ((uint32)M2M_MAKE_VERSION((drv_major), (drv_minor), (drv_patch))) << M2M_DRV_VERSION_SHIFT)) + +#define REL_19_4_1_VER M2M_MAKE_VERSION_INFO(19,4,1,19,3,0) +#define REL_19_4_0_VER M2M_MAKE_VERSION_INFO(19,4,0,19,3,0) +#define REL_19_3_1_VER M2M_MAKE_VERSION_INFO(19,3,1,19,3,0) +#define REL_19_3_0_VER M2M_MAKE_VERSION_INFO(19,3,0,19,3,0) +#define REL_19_2_2_VER M2M_MAKE_VERSION_INFO(19,2,2,19,2,0) +#define REL_19_2_1_VER M2M_MAKE_VERSION_INFO(19,2,1,19,2,0) +#define REL_19_2_0_VER M2M_MAKE_VERSION_INFO(19,2,0,19,2,0) +#define REL_19_1_0_VER M2M_MAKE_VERSION_INFO(19,1,0,18,2,0) +#define REL_19_0_0_VER M2M_MAKE_VERSION_INFO(19,0,0,18,1,1) + +/*======*======*======*======* + FIRMWARE VERSION NO INFO + *======*======*======*======*/ + +#define M2M_FIRMWARE_VERSION_MAJOR_NO (19) +/*!< Firmware Major release version number. +*/ + + +#define M2M_FIRMWARE_VERSION_MINOR_NO (4) +/*!< Firmware Minor release version number. +*/ + +#define M2M_FIRMWARE_VERSION_PATCH_NO (4) +/*!< Firmware patch release version number. +*/ + +/*======*======*======*======* + SUPPORTED DRIVER VERSION NO INFO + *======*======*======*======*/ + +#define M2M_DRIVER_VERSION_MAJOR_NO (19) +/*!< Driver Major release version number. +*/ + + +#define M2M_DRIVER_VERSION_MINOR_NO (4) +/*!< Driver Minor release version number. +*/ + +#define M2M_DRIVER_VERSION_PATCH_NO (4) +/*!< Driver patch release version number. +*/ + + +#if !defined(M2M_FIRMWARE_VERSION_MAJOR_NO) || !defined(M2M_FIRMWARE_VERSION_MINOR_NO) +#error Undefined version number +#endif + +#define M2M_BUFFER_MAX_SIZE (1600UL - 4) +/*!< Maximum size for the shared packet buffer. + */ + + +#define M2M_MAC_ADDRES_LEN 6 +/*!< The size fo 802 MAC address. + */ + +#define M2M_ETHERNET_HDR_OFFSET 34 +/*!< The offset of the Ethernet header within the WLAN Tx Buffer. + */ + + +#define M2M_ETHERNET_HDR_LEN 14 +/*!< Length of the Etherenet header in bytes. +*/ + + +#define M2M_MAX_SSID_LEN 33 +/*!< Maximum size for the Wi-Fi SSID including the NULL termination. + */ + + +#define M2M_MAX_PSK_LEN 65 +/*!< Maximum size for the WPA PSK including the NULL termination. + */ + + +#define M2M_DEVICE_NAME_MAX 48 +/*!< Maximum Size for the device name including the NULL termination. + */ + + +#define M2M_LISTEN_INTERVAL 1 +/*!< The STA uses the Listen Interval parameter to indicate to the AP how + many beacon intervals it shall sleep before it retrieves the queued frames + from the AP. +*/ + + +#define M2M_1X_USR_NAME_MAX 21 +/*!< The maximum size of the user name including the NULL termination. + It is used for RADIUS authentication in case of connecting the device to + an AP secured with WPA-Enterprise. +*/ + + +#define M2M_1X_PWD_MAX 41 +/*!< The maximum size of the password including the NULL termination. + It is used for RADIUS authentication in case of connecting the device to + an AP secured with WPA-Enterprise. +*/ + +#define M2M_CUST_IE_LEN_MAX 252 +/*!< The maximum size of IE (Information Element). +*/ +/********************* + * + * WIFI GROUP requests + */ + +#define M2M_CONFIG_CMD_BASE 1 +/*!< The base value of all the host configuration commands opcodes. +*/ +#define M2M_STA_CMD_BASE 40 +/*!< The base value of all the station mode host commands opcodes. +*/ +#define M2M_AP_CMD_BASE 70 +/*!< The base value of all the Access Point mode host commands opcodes. +*/ +#define M2M_P2P_CMD_BASE 90 +/*!< The base value of all the P2P mode host commands opcodes. +*/ +#define M2M_SERVER_CMD_BASE 100 +/*!< The base value of all the power save mode host commands codes. +*/ +/********************** + * OTA GROUP requests + */ +#define M2M_OTA_CMD_BASE 100 +/*!< The base value of all the OTA mode host commands opcodes. + * The OTA Have special group so can extended from 1-M2M_MAX_GRP_NUM_REQ +*/ +/*********************** + * + * CRYPTO group requests + */ +#define M2M_CRYPTO_CMD_BASE 1 +/*!< The base value of all the crypto mode host commands opcodes. + * The crypto Have special group so can extended from 1-M2M_MAX_GRP_NUM_REQ +*/ + +#define M2M_MAX_GRP_NUM_REQ (127) +/*!< max number of request in one group equal to 127 as the last bit reserved for config or data pkt +*/ + +#define WEP_40_KEY_STRING_SIZE ((uint8)10) +/*!< Indicate the wep key size in bytes for 40 bit string passphrase. +*/ + +#define WEP_104_KEY_STRING_SIZE ((uint8)26) +/*!< Indicate the wep key size in bytes for 104 bit string passphrase. +*/ +#define WEP_KEY_MAX_INDEX ((uint8)4) +/*!< Indicate the max key index value for WEP authentication +*/ +#define M2M_SHA256_CONTEXT_BUFF_LEN (128) +/*!< sha256 context size +*/ +#define M2M_SCAN_DEFAULT_NUM_SLOTS (2) +/*!< The default. number of scan slots performed by the WINC board. +*/ +#define M2M_SCAN_DEFAULT_SLOT_TIME (30) +/*!< The default. duration in miliseconds of a scan slots performed by the WINC board. +*/ +#define M2M_SCAN_DEFAULT_NUM_PROBE (2) +/*!< The default. number of scan slots performed by the WINC board. +*/ + + +/*======*======*======*======* + CONNECTION ERROR DEFINITIONS + *======*======*======*======*/ +typedef enum { + M2M_DEFAULT_CONN_INPROGRESS = ((sint8)-23), + /*!< + A failure that indicates that a default connection or forced connection is in progress + */ + M2M_DEFAULT_CONN_FAIL, + /*!< + A failure response that indicates that the winc failed to connect to the cached network + */ + M2M_DEFAULT_CONN_SCAN_MISMATCH, + /*!< + A failure response that indicates that no one of the cached networks + was found in the scan results, as a result to the function call m2m_default_connect. + */ + M2M_DEFAULT_CONN_EMPTY_LIST + /*!< + A failure response that indicates an empty network list as + a result to the function call m2m_default_connect. + */ + +}tenuM2mDefaultConnErrcode; + + + + +/*======*======*======*======* + OTA DEFINITIONS + *======*======*======*======*/ + +#define OTA_STATUS_VALID (0x12526285) +/*!< + Magic value updated in the Control structure in case of ROLLACK image Valid +*/ +#define OTA_STATUS_INVALID (0x23987718) +/*!< + Magic value updated in the Control structure in case of ROLLACK image InValid +*/ +#define OTA_MAGIC_VALUE (0x1ABCDEF9) +/*!< + Magic value set at the beginning of the OTA image header +*/ + +#define OTA_FORMAT_VER_0 (0) /*Till 19.2.2 format*/ +#define OTA_FORMAT_VER_1 (1) /*starting from 19.3.0 CRC is used and sequence number is used*/ +/*!< + Control structure format version +*/ +#define OTA_SHA256_DIGEST_SIZE (32) +/*!< + Sha256 digest size in the OTA image, + the sha256 digest is set at the beginning of image before the OTA header +*/ + +#define OTA_SUCCESS (0) +/*!< + OTA Success status +*/ +#define OTA_ERR_WORKING_IMAGE_LOAD_FAIL ((sint8)-1) +/*!< + Failure to load the firmware image +*/ +#define OTA_ERR_INVAILD_CONTROL_SEC ((sint8)-2) +/*!< + Control structure is being corrupted +*/ +#define M2M_ERR_OTA_SWITCH_FAIL ((sint8)-3) +/*!< + switching to the updated image failed as may be the image is invalid +*/ +#define M2M_ERR_OTA_START_UPDATE_FAIL ((sint8)-4) +/*!< + OTA update fail due to multiple reasons + - Connection failure + - Image integrity fail + +*/ +#define M2M_ERR_OTA_ROLLBACK_FAIL ((sint8)-5) +/*!< + Roll-back failed due to Roll-back image is not valid +*/ +#define M2M_ERR_OTA_INVAILD_FLASH_SIZE ((sint8)-6) +/*!< + The OTA Support at least 4MB flash size, if the above error will appear if the current flash is less than 4M +*/ +#define M2M_ERR_OTA_INVAILD_ARG ((sint8)-7) +/*!< + Invalid argument in any OTA Function +*/ +/**@}*/ + +/** +* @addtogroup WlanEnums Enumerations and Typedefs +* @ingroup m2m_wifi +*/ + /**@{*/ + +/*! +@enum \ + tenuM2mConnChangedErrcode + +@brief + +*/ +typedef enum { + M2M_ERR_SCAN_FAIL = ((uint8)1), + /*!< Indicate that the WINC board has failed to perform the scan operation. + */ + M2M_ERR_JOIN_FAIL, + /*!< Indicate that the WINC board has failed to join the BSS . + */ + M2M_ERR_AUTH_FAIL, + /*!< Indicate that the WINC board has failed to authenticate with the AP. + */ + M2M_ERR_ASSOC_FAIL, + /*!< Indicate that the WINC board has failed to associate with the AP. + */ + M2M_ERR_CONN_INPROGRESS, + /*!< Indicate that the WINC board has another connection request in progress. + */ +}tenuM2mConnChangedErrcode; +/*! +@enum \ + tenuM2mWepKeyIndex + +@brief + +*/ +typedef enum { + M2M_WIFI_WEP_KEY_INDEX_1 = ((uint8) 1), + M2M_WIFI_WEP_KEY_INDEX_2, + M2M_WIFI_WEP_KEY_INDEX_3, + M2M_WIFI_WEP_KEY_INDEX_4, + /*!< Index for WEP key Authentication + */ +}tenuM2mWepKeyIndex; + +/*! +@enum \ + tenuM2mPwrMode + +@brief + +*/ +typedef enum { + PWR_AUTO = ((uint8) 1), + /*!< FW will decide the best power mode to use internally. */ + PWR_LOW1, + /*low power mode #1*/ + PWR_LOW2, + /*low power mode #2*/ + PWR_HIGH, + /* high power mode*/ +}tenuM2mPwrMode; + +/*! +@struct \ + tstrM2mPwrState + +@brief + Power Mode +*/ +typedef struct { + uint8 u8PwrMode; + /*!< power Save Mode + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mPwrMode; +/*! +@enum \ + tenuM2mTxPwrLevel + +@brief + +*/ +typedef enum { + TX_PWR_HIGH = ((uint8) 1), + /*!< PPA Gain 6dbm PA Gain 18dbm */ + TX_PWR_MED, + /*!< PPA Gain 6dbm PA Gain 12dbm */ + TX_PWR_LOW, + /*!< PPA Gain 6dbm PA Gain 6dbm */ +}tenuM2mTxPwrLevel; + +/*! +@struct \ + tstrM2mTxPwrLevel + +@brief + Tx power level +*/ +typedef struct { + uint8 u8TxPwrLevel; + /*!< Tx power level + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mTxPwrLevel; + +/*! +@struct \ + tstrM2mEnableLogs + +@brief + Enable Firmware logs +*/ +typedef struct { + uint8 u8Enable; + /*!< Enable/Disable firmware logs + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mEnableLogs; + +/*! +@struct \ + tstrM2mBatteryVoltage + +@brief + Battery Voltage +*/ +typedef struct { + //Note: on SAMD D21 the size of double is 8 Bytes + uint16 u16BattVolt; + /*!< Battery Voltage + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mBatteryVoltage; + +/*! +@enum \ + tenuM2mReqGroup + +@brief +*/ +typedef enum{ + M2M_REQ_GROUP_MAIN = 0, + M2M_REQ_GROUP_WIFI, + M2M_REQ_GROUP_IP, + M2M_REQ_GROUP_HIF, + M2M_REQ_GROUP_OTA, + M2M_REQ_GROUP_SSL, + M2M_REQ_GROUP_CRYPTO, + M2M_REQ_GROUP_SIGMA, +}tenuM2mReqGroup; + +/*! +@enum \ + tenuM2mReqpkt + +@brief +*/ +typedef enum{ + M2M_REQ_CONFIG_PKT, + M2M_REQ_DATA_PKT = 0x80 /*BIT7*/ +}tenuM2mReqpkt; +/*! +@enum \ + tenuM2mConfigCmd + +@brief + This enum contains all the host commands used to configure the WINC board. + +*/ +typedef enum { + M2M_WIFI_REQ_RESTART = M2M_CONFIG_CMD_BASE, + /*!< + Restart the WINC MAC layer, it's doesn't restart the IP layer. + */ + M2M_WIFI_REQ_SET_MAC_ADDRESS, + /*!< + Set the WINC mac address (not possible for production effused boards). + */ + M2M_WIFI_REQ_CURRENT_RSSI, + /*!< + Request the current connected AP RSSI. + */ + M2M_WIFI_RESP_CURRENT_RSSI, + /*!< + Response to M2M_WIFI_REQ_CURRENT_RSSI with the RSSI value. + */ + M2M_WIFI_REQ_GET_CONN_INFO, + /*!< Request connection information command. + */ + M2M_WIFI_RESP_CONN_INFO, + + /*!< Connect with default AP response. + */ + M2M_WIFI_REQ_SET_DEVICE_NAME, + /*!< + Set the WINC device name property. + */ + M2M_WIFI_REQ_START_PROVISION_MODE, + /*!< + Start the provisioning mode for the M2M Device. + */ + M2M_WIFI_RESP_PROVISION_INFO, + /*!< + Send the provisioning information to the host. + */ + M2M_WIFI_REQ_STOP_PROVISION_MODE, + /*!< + Stop the current running provision mode. + */ + M2M_WIFI_REQ_SET_SYS_TIME, + /*!< + Set time of day from host. + */ + M2M_WIFI_REQ_ENABLE_SNTP_CLIENT, + /*!< + Enable the simple network time protocol to get the + time from the Internet. this is required for security purposes. + */ + M2M_WIFI_REQ_DISABLE_SNTP_CLIENT, + /*!< + Disable the simple network time protocol for applications that + do not need it. + */ + M2M_WIFI_RESP_MEMORY_RECOVER, + /*!< + * Reserved for debuging + * */ + M2M_WIFI_REQ_CUST_INFO_ELEMENT, + /*!< Add Custom ELement to Beacon Managament Frame. + */ + M2M_WIFI_REQ_SCAN, + /*!< Request scan command. + */ + M2M_WIFI_RESP_SCAN_DONE, + /*!< Scan complete notification response. + */ + M2M_WIFI_REQ_SCAN_RESULT, + /*!< Request Scan results command. + */ + M2M_WIFI_RESP_SCAN_RESULT, + /*!< Request Scan results resopnse. + */ + M2M_WIFI_REQ_SET_SCAN_OPTION, + /*!< Set Scan options "slot time, slot number .. etc" . + */ + M2M_WIFI_REQ_SET_SCAN_REGION, + /*!< Set scan region. + */ + M2M_WIFI_REQ_SET_POWER_PROFILE, + /*!< The API shall set power mode to one of 3 modes + */ + M2M_WIFI_REQ_SET_TX_POWER, + /*!< API to set TX power. + */ + M2M_WIFI_REQ_SET_BATTERY_VOLTAGE, + /*!< API to set Battery Voltage. + */ + M2M_WIFI_REQ_SET_ENABLE_LOGS, + /*!< API to set Battery Voltage. + */ + M2M_WIFI_REQ_GET_SYS_TIME, + /*!< + REQ GET time of day from WINC. + */ + M2M_WIFI_RESP_GET_SYS_TIME, + /*!< + RESP time of day from host. + */ + M2M_WIFI_REQ_SEND_ETHERNET_PACKET, + /*!< Send Ethernet packet in bypass mode. + */ + M2M_WIFI_RESP_ETHERNET_RX_PACKET, + /*!< Receive Ethernet packet in bypass mode. + */ + M2M_WIFI_REQ_SET_MAC_MCAST, + /*!< Set the WINC multicast filters. + */ + M2M_WIFI_REQ_GET_PRNG, + /*!< Request PRNG. + */ + M2M_WIFI_RESP_GET_PRNG, + /*!< Response for PRNG. + */ + M2M_WIFI_MAX_CONFIG_ALL, +}tenuM2mConfigCmd; + +/*! +@enum \ + tenuM2mStaCmd + +@brief + This enum contains all the WINC commands while in Station mode. +*/ +typedef enum { + M2M_WIFI_REQ_CONNECT = M2M_STA_CMD_BASE, + /*!< Connect with AP command. + */ + M2M_WIFI_REQ_DEFAULT_CONNECT, + /*!< Connect with default AP command. + */ + M2M_WIFI_RESP_DEFAULT_CONNECT, + /*!< Request connection information response. + */ + M2M_WIFI_REQ_DISCONNECT, + /*!< Request to disconnect from AP command. + */ + M2M_WIFI_RESP_CON_STATE_CHANGED, + /*!< Connection state changed response. + */ + M2M_WIFI_REQ_SLEEP, + /*!< Set PS mode command. + */ + M2M_WIFI_REQ_WPS_SCAN, + /*!< Request WPS scan command. + */ + M2M_WIFI_REQ_WPS, + /*!< Request WPS start command. + */ + M2M_WIFI_REQ_START_WPS, + /*!< This command is for internal use by the WINC and + should not be used by the host driver. + */ + M2M_WIFI_REQ_DISABLE_WPS, + /*!< Request to disable WPS command. + */ + M2M_WIFI_REQ_DHCP_CONF, + /*!< Response indicating that IP address was obtained. + */ + M2M_WIFI_RESP_IP_CONFIGURED, + /*!< This command is for internal use by the WINC and + should not be used by the host driver. + */ + M2M_WIFI_RESP_IP_CONFLICT, + /*!< Response indicating a conflict in obtained IP address. + The user should re attempt the DHCP request. + */ + M2M_WIFI_REQ_ENABLE_MONITORING, + /*!< Request to enable monitor mode command. + */ + M2M_WIFI_REQ_DISABLE_MONITORING, + /*!< Request to disable monitor mode command. + */ + M2M_WIFI_RESP_WIFI_RX_PACKET, + /*!< Indicate that a packet was received in monitor mode. + */ + M2M_WIFI_REQ_SEND_WIFI_PACKET, + /*!< Send packet in monitor mode. + */ + M2M_WIFI_REQ_LSN_INT, + /*!< Set WiFi listen interval. + */ + M2M_WIFI_REQ_DOZE, + /*!< Used to force the WINC to sleep in manual PS mode. + */ + M2M_WIFI_MAX_STA_ALL, +} tenuM2mStaCmd; + +/*! +@enum \ + tenuM2mApCmd + +@brief + This enum contains all the WINC commands while in AP mode. +*/ +typedef enum { + M2M_WIFI_REQ_ENABLE_AP = M2M_AP_CMD_BASE, + /*!< Enable AP mode command. + */ + M2M_WIFI_REQ_DISABLE_AP, + /*!< Disable AP mode command. + */ + M2M_WIFI_MAX_AP_ALL, +}tenuM2mApCmd; + +/*! +@enum \ + tenuM2mP2pCmd + +@brief + This enum contains all the WINC commands while in P2P mode. +*/ +typedef enum { + M2M_WIFI_REQ_P2P_INT_CONNECT = M2M_P2P_CMD_BASE, + /*!< This command is for internal use by the WINC and + should not be used by the host driver. + */ + M2M_WIFI_REQ_ENABLE_P2P, + /*!< Enable P2P mode command. + */ + M2M_WIFI_REQ_DISABLE_P2P, + /*!< Disable P2P mode command. + */ + M2M_WIFI_REQ_P2P_REPOST, + /*!< This command is for internal use by the WINC and + should not be used by the host driver. + */ + M2M_WIFI_MAX_P2P_ALL, +}tenuM2mP2pCmd; + + + +/*! +@enum \ + tenuM2mServerCmd + +@brief + This enum contains all the WINC commands while in PS mode. + These command are currently not supported. +*/ +typedef enum { + M2M_WIFI_REQ_CLIENT_CTRL = M2M_SERVER_CMD_BASE, + M2M_WIFI_RESP_CLIENT_INFO, + M2M_WIFI_REQ_SERVER_INIT, + M2M_WIFI_MAX_SERVER_ALL +}tenuM2mServerCmd; + + + +/*! +@enum \ + tenuM2mOtaCmd + +@brief + +*/ +typedef enum { + M2M_OTA_REQ_NOTIF_SET_URL = M2M_OTA_CMD_BASE, + M2M_OTA_REQ_NOTIF_CHECK_FOR_UPDATE, + M2M_OTA_REQ_NOTIF_SCHED, + M2M_OTA_REQ_START_UPDATE, + M2M_OTA_REQ_SWITCH_FIRMWARE, + M2M_OTA_REQ_ROLLBACK, + M2M_OTA_RESP_NOTIF_UPDATE_INFO, + M2M_OTA_RESP_UPDATE_STATUS, + M2M_OTA_REQ_TEST, + M2M_OTA_MAX_ALL, +}tenuM2mOtaCmd; + +/*! +@enum \ + tenuM2mCryptoCmd + +@brief + +*/ +typedef enum { + M2M_CRYPTO_REQ_SHA256_INIT = M2M_CRYPTO_CMD_BASE, + M2M_CRYPTO_RESP_SHA256_INIT, + M2M_CRYPTO_REQ_SHA256_UPDATE, + M2M_CRYPTO_RESP_SHA256_UPDATE, + M2M_CRYPTO_REQ_SHA256_FINSIH, + M2M_CRYPTO_RESP_SHA256_FINSIH, + M2M_CRYPTO_REQ_RSA_SIGN_GEN, + M2M_CRYPTO_RESP_RSA_SIGN_GEN, + M2M_CRYPTO_REQ_RSA_SIGN_VERIFY, + M2M_CRYPTO_RESP_RSA_SIGN_VERIFY, + M2M_CRYPTO_MAX_ALL, +}tenuM2mCryptoCmd; + +/*! +@enum \ + tenuM2mIpCmd + +@brief + +*/ +typedef enum { + /* Request IDs corresponding to the IP GROUP. */ + M2M_IP_REQ_STATIC_IP_CONF = ((uint8) 10), + M2M_IP_REQ_ENABLE_DHCP, + M2M_IP_REQ_DISABLE_DHCP +} tenuM2mIpCmd; + +/*! +@enum \ + tenuM2mSigmaCmd + +@brief + +*/ +typedef enum { + /* Request IDs corresponding to the IP GROUP. */ + M2M_SIGMA_ENABLE = ((uint8) 3), + M2M_SIGMA_TA_START, + M2M_SIGMA_TA_STATS, + M2M_SIGMA_TA_RECEIVE_STOP, + M2M_SIGMA_ICMP_ARP, + M2M_SIGMA_ICMP_RX, + M2M_SIGMA_ICMP_TX, + M2M_SIGMA_UDP_TX, + M2M_SIGMA_UDP_TX_DEFER, + M2M_SIGMA_SECURITY_POLICY, + M2M_SIGMA_SET_SYSTIME +} tenuM2mSigmaCmd; + + +/*! +@enum \ + tenuM2mConnState + +@brief + Wi-Fi Connection State. +*/ +typedef enum { + M2M_WIFI_DISCONNECTED = 0, + /*!< Wi-Fi state is disconnected. + */ + M2M_WIFI_CONNECTED, + /*!< Wi-Fi state is connected. + */ + M2M_WIFI_UNDEF = 0xff + /*!< Undefined Wi-Fi State. + */ +}tenuM2mConnState; + +/*! +@enum \ + tenuM2mSecType + +@brief + Wi-Fi Supported Security types. +*/ +typedef enum { + M2M_WIFI_SEC_INVALID = 0, + /*!< Invalid security type. + */ + M2M_WIFI_SEC_OPEN, + /*!< Wi-Fi network is not secured. + */ + M2M_WIFI_SEC_WPA_PSK, + /*!< Wi-Fi network is secured with WPA/WPA2 personal(PSK). + */ + M2M_WIFI_SEC_WEP, + /*!< Security type WEP (40 or 104) OPEN OR SHARED. + */ + M2M_WIFI_SEC_802_1X + /*!< Wi-Fi network is secured with WPA/WPA2 Enterprise.IEEE802.1x user-name/password authentication. + */ +}tenuM2mSecType; + + +/*! +@enum \ + tenuM2mSecType + +@brief + Wi-Fi Supported SSID types. +*/ +typedef enum { + SSID_MODE_VISIBLE = 0, + /*!< SSID is visible to others. + */ + SSID_MODE_HIDDEN + /*!< SSID is hidden. + */ +}tenuM2mSsidMode; + +/*! +@enum \ + tenuM2mScanCh + +@brief + Wi-Fi RF Channels. +*/ +typedef enum { + M2M_WIFI_CH_1 = ((uint8) 0), + M2M_WIFI_CH_2, + M2M_WIFI_CH_3, + M2M_WIFI_CH_4, + M2M_WIFI_CH_5, + M2M_WIFI_CH_6, + M2M_WIFI_CH_7, + M2M_WIFI_CH_8, + M2M_WIFI_CH_9, + M2M_WIFI_CH_10, + M2M_WIFI_CH_11, + M2M_WIFI_CH_12, + M2M_WIFI_CH_13, + M2M_WIFI_CH_14, + M2M_WIFI_CH_ALL = ((uint8) 255) +}tenuM2mScanCh; + +/*! +@enum \ + tenuM2mScanRegion + +@brief + Wi-Fi RF Channels. +*/ +typedef enum { + + REG_CH_1 = ((uint16) 1 << 0), + REG_CH_2 = ((uint16) 1 << 1), + REG_CH_3 = ((uint16) 1 << 2), + REG_CH_4 = ((uint16) 1 << 3), + REG_CH_5 = ((uint16) 1 << 4), + REG_CH_6 = ((uint16) 1 << 5), + REG_CH_7 = ((uint16) 1 << 6), + REG_CH_8 = ((uint16) 1 << 7), + REG_CH_9 = ((uint16) 1 << 8), + REG_CH_10 = ((uint16) 1 << 9), + REG_CH_11 = ((uint16) 1 << 10), + REG_CH_12 = ((uint16) 1 << 11), + REG_CH_13 = ((uint16) 1 << 12), + REG_CH_14 = ((uint16) 1 << 13), + REG_CH_ALL = ((uint16) 0x3FFF), + NORTH_AMERICA = ((uint16) 0x7FF), + /** 11 channel + */ + EUROPE = ((uint16) 0x1FFF), + /** 13 channel + */ + ASIA = ((uint16) 0x3FFF) + /* 14 channel + */ +}tenuM2mScanRegion; + + +/*! +@enum \ + tenuPowerSaveModes + +@brief + Power Save Modes. +*/ +typedef enum { + M2M_NO_PS, + /*!< Power save is disabled. + */ + M2M_PS_AUTOMATIC, + /*!< Power save is done automatically by the WINC. + This mode doesn't disable all of the WINC modules and + use higher amount of power than the H_AUTOMATIC and + the DEEP_AUTOMATIC modes.. + */ + M2M_PS_H_AUTOMATIC, + /*!< Power save is done automatically by the WINC. + Achieve higher power save than the AUTOMATIC mode + by shutting down more parts of the WINC board. + */ + M2M_PS_DEEP_AUTOMATIC, + /*!< Power save is done automatically by the WINC. + Achieve the highest possible power save. + */ + M2M_PS_MANUAL + /*!< Power save is done manually by the user. + */ +}tenuPowerSaveModes; + +/*! +@enum \ + tenuM2mWifiMode + +@brief + Wi-Fi Operation Mode. +*/ +typedef enum { + M2M_WIFI_MODE_NORMAL = ((uint8) 1), + /*!< Normal Mode means to run customer firmware version. + */ + M2M_WIFI_MODE_ATE_HIGH, + /*!< Config Mode in HIGH POWER means to run production test firmware version which is known as ATE (Burst) firmware. + */ + M2M_WIFI_MODE_ATE_LOW, + /*!< Config Mode in LOW POWER means to run production test firmware version which is known as ATE (Burst) firmware. + */ + M2M_WIFI_MODE_ETHERNET, + /*!< etherent Mode + */ + M2M_WIFI_MODE_MAX, +}tenuM2mWifiMode; + +/*! +@enum \ + tenuWPSTrigger + +@brief + WPS Triggering Methods. +*/ +typedef enum{ + WPS_PIN_TRIGGER = 0, + /*!< WPS is triggered in PIN method. + */ + WPS_PBC_TRIGGER = 4 + /*!< WPS is triggered via push button. + */ +}tenuWPSTrigger; + + +/*! +@struct \ + tstrM2mWifiWepParams + +@brief + WEP security key parameters. +*/ +typedef struct{ + uint8 u8KeyIndx; + /*!< Wep key Index. + */ + uint8 u8KeySz; + /*!< Wep key Size. + */ + uint8 au8WepKey[WEP_104_KEY_STRING_SIZE + 1]; + /*!< WEP Key represented as a NULL terminated ASCII string. + */ + uint8 __PAD24__[3]; + /*!< Padding bytes to keep the structure word alligned. + */ +}tstrM2mWifiWepParams; + + +/*! +@struct \ + tstr1xAuthCredentials + +@brief + Credentials for the user to authenticate with the AAA server (WPA-Enterprise Mode IEEE802.1x). +*/ +typedef struct{ + uint8 au8UserName[M2M_1X_USR_NAME_MAX]; + /*!< User Name. It must be Null terminated string. + */ + uint8 au8Passwd[M2M_1X_PWD_MAX]; + /*!< Password corresponding to the user name. It must be Null terminated string. + */ +}tstr1xAuthCredentials; + + +/*! +@union \ + tuniM2MWifiAuth + +@brief + Wi-Fi Security Parameters for all supported security modes. +*/ +typedef union{ + uint8 au8PSK[M2M_MAX_PSK_LEN]; + /*!< Pre-Shared Key in case of WPA-Personal security. + */ + tstr1xAuthCredentials strCred1x; + /*!< Credentials for RADIUS server authentication in case of WPA-Enterprise security. + */ + tstrM2mWifiWepParams strWepInfo; + /*!< WEP key parameters in case of WEP security. + */ +}tuniM2MWifiAuth; + + +/*! +@struct \ + tstrM2MWifiSecInfo + +@brief + Authentication credentials to connect to a Wi-Fi network. +*/ +typedef struct{ + tuniM2MWifiAuth uniAuth; + /*!< Union holding all possible authentication parameters corresponding the current security types. + */ + uint8 u8SecType; + /*!< Wi-Fi network security type. See tenuM2mSecType for supported security types. + */ +#define __PADDING__ (4 - ((sizeof(tuniM2MWifiAuth) + 1) % 4)) + uint8 __PAD__[__PADDING__]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2MWifiSecInfo; + + +/*! +@struct \ + tstrM2mWifiConnect + +@brief + Wi-Fi Connect Request +*/ +typedef struct{ + tstrM2MWifiSecInfo strSec; + /*!< Security parameters for authenticating with the AP. + */ + uint16 u16Ch; + /*!< RF Channel for the target SSID. + */ + uint8 au8SSID[M2M_MAX_SSID_LEN]; + /*!< SSID of the desired AP. It must be NULL terminated string. + */ + uint8 u8NoSaveCred; +#define __CONN_PAD_SIZE__ (4 - ((sizeof(tstrM2MWifiSecInfo) + M2M_MAX_SSID_LEN + 3) % 4)) + uint8 __PAD__[__CONN_PAD_SIZE__]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mWifiConnect; + + +/*! +@struct \ + tstrM2MWPSConnect + +@brief + WPS Configuration parameters + +@sa + tenuWPSTrigger +*/ +typedef struct { + uint8 u8TriggerType; + /*!< WPS triggering method (Push button or PIN) + */ + char acPinNumber[8]; + /*!< WPS PIN No (for PIN method) + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2MWPSConnect; + + +/*! +@struct \ + tstrM2MWPSInfo + +@brief WPS Result + + This structure is passed to the application in response to a WPS request. If the WPS session is completed successfully, the + structure will have Non-ZERO authentication type. If the WPS Session fails (due to error or timeout) the authentication type + is set to ZERO. + +@sa + tenuM2mSecType +*/ +typedef struct{ + uint8 u8AuthType; + /*!< Network authentication type. + */ + uint8 u8Ch; + /*!< RF Channel for the AP. + */ + uint8 au8SSID[M2M_MAX_SSID_LEN]; + /*!< SSID obtained from WPS. + */ + uint8 au8PSK[M2M_MAX_PSK_LEN]; + /*!< PSK for the network obtained from WPS. + */ +}tstrM2MWPSInfo; + + +/*! +@struct \ + tstrM2MDefaultConnResp + +@brief + Response error of the m2m_default_connect + +@sa + M2M_DEFAULT_CONN_SCAN_MISMATCH + M2M_DEFAULT_CONN_EMPTY_LIST +*/ +typedef struct{ + sint8 s8ErrorCode; + /*!< + Default connect error code. possible values are: + - M2M_DEFAULT_CONN_EMPTY_LIST + - M2M_DEFAULT_CONN_SCAN_MISMATCH + */ + uint8 __PAD24__[3]; +}tstrM2MDefaultConnResp; + +/*! +@struct \ + tstrM2MScan + +@brief + Wi-Fi Scan Request + +@sa + tenuM2mScanCh +*/ +typedef struct { + uint8 u8NumOfSlot; + /*|< The min number of slots is 2 for every channel, + every slot the soc will send Probe Request on air, and wait/listen for PROBE RESP/BEACONS for the u16slotTime + */ + uint8 u8SlotTime; + /*|< the time that the Soc will wait on every channel listening to the frames on air + when that time increaseed number of AP will increased in the scan results + min time is 10 ms and the max is 250 ms + */ + uint8 u8ProbesPerSlot; + /*!< Number of probe requests to be sent per channel scan slot. + */ + sint8 s8RssiThresh; + /*! < The RSSI threshold of the AP which will be connected to directly. + */ + +}tstrM2MScanOption; + +/*! +@struct \ + tstrM2MScanRegion + +@brief + Wi-Fi channel regulation region information. + +@sa + tenuM2mScanRegion +*/ +typedef struct { + uint16 u16ScanRegion; + /*|< Specifies the number of channels allowed in the region (e.g. North America = 11 ... etc.). + */ + uint8 __PAD16__[2]; + +}tstrM2MScanRegion; + +/*! +@struct \ + tstrM2MScan + +@brief + Wi-Fi Scan Request + +@sa + tenuM2mScanCh +*/ +typedef struct { + uint8 u8ChNum; + /*!< The Wi-Fi RF Channel number + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ + +}tstrM2MScan; + +/*! +@struct \ + tstrCyptoResp + +@brief + crypto response +*/ +typedef struct { + sint8 s8Resp; + /***/ + uint8 __PAD24__[3]; + /* + */ +}tstrCyptoResp; + + +/*! +@struct \ + tstrM2mScanDone + +@brief + Wi-Fi Scan Result +*/ +typedef struct{ + uint8 u8NumofCh; + /*!< Number of found APs + */ + sint8 s8ScanState; + /*!< Scan status + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mScanDone; + + +/*! +@struct \ + tstrM2mReqScanResult + +@brief Scan Result Request + + The Wi-Fi Scan results list is stored in Firmware. The application can request a certain scan result by its index. +*/ +typedef struct { + uint8 u8Index; + /*!< Index of the desired scan result + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mReqScanResult; + + +/*! +@struct \ + tstrM2mWifiscanResult + +@brief Wi-Fi Scan Result + + Information corresponding to an AP in the Scan Result list identified by its order (index) in the list. +*/ +typedef struct { + uint8 u8index; + /*!< AP index in the scan result list. + */ + sint8 s8rssi; + /*!< AP signal strength. + */ + uint8 u8AuthType; + /*!< AP authentication type. + */ + uint8 u8ch; + /*!< AP RF channel. + */ + uint8 au8BSSID[6]; + /*!< BSSID of the AP. + */ + uint8 au8SSID[M2M_MAX_SSID_LEN]; + /*!< AP ssid. + */ + uint8 _PAD8_; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mWifiscanResult; + + +/*! +@struct \ + tstrM2mWifiStateChanged + +@brief + Wi-Fi Connection State + +@sa + M2M_WIFI_DISCONNECTED, M2M_WIFI_CONNECTED, M2M_WIFI_REQ_CON_STATE_CHANGED,tenuM2mConnChangedErrcode +*/ +typedef struct { + uint8 u8CurrState; + /*!< Current Wi-Fi connection state + */ + uint8 u8ErrCode; + /*!< Error type review tenuM2mConnChangedErrcode + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mWifiStateChanged; + + +/*! +@struct \ + tstrM2mPsType + +@brief + Power Save Configuration + +@sa + tenuPowerSaveModes +*/ +typedef struct{ + uint8 u8PsType; + /*!< Power save operating mode + */ + uint8 u8BcastEn; + /*!< + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mPsType; + +/*! +@struct \ + tstrM2mSlpReqTime + +@brief + Manual power save request sleep time + +*/ +typedef struct { + /*!< Sleep time in ms + */ + uint32 u32SleepTime; + +} tstrM2mSlpReqTime; + +/*! +@struct \ + tstrM2mLsnInt + +@brief Listen interval + + It is the value of the Wi-Fi STA listen interval for power saving. It is given in units of Beacon period. + Periodically after the listen interval fires, the WINC is wakeup and listen to the beacon and check for any buffered frames for it from the AP. +*/ +typedef struct { + uint16 u16LsnInt; + /*!< Listen interval in Beacon period count. + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mLsnInt; + + +/*! +@struct \ + tstrM2MWifiMonitorModeCtrl + +@brief Wi-Fi Monitor Mode Filter + + This structure sets the filtering criteria for WLAN packets when monitoring mode is enable. + The received packets matching the filtering parameters, are passed directly to the application. +*/ +typedef struct{ + uint8 u8ChannelID; + /* !< RF Channel ID. It must use values from tenuM2mScanCh + */ + uint8 u8FrameType; + /*!< It must use values from tenuWifiFrameType. + */ + uint8 u8FrameSubtype; + /*!< It must use values from tenuSubTypes. + */ + uint8 au8SrcMacAddress[6]; + /* ZERO means DO NOT FILTER Source address. + */ + uint8 au8DstMacAddress[6]; + /* ZERO means DO NOT FILTER Destination address. + */ + uint8 au8BSSID[6]; + /* ZERO means DO NOT FILTER BSSID. + */ + uint8 u8EnRecvHdr; + /* + Enable recv the full hder before the payload + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2MWifiMonitorModeCtrl; + + +/*! +@struct \ + tstrM2MWifiRxPacketInfo + +@brief Wi-Fi RX Frame Header + + The M2M application has the ability to allow Wi-Fi monitoring mode for receiving all Wi-Fi Raw frames matching a well defined filtering criteria. + When a target Wi-Fi packet is received, the header information are extracted and assigned in this structure. +*/ +typedef struct{ + uint8 u8FrameType; + /*!< It must use values from tenuWifiFrameType. + */ + uint8 u8FrameSubtype; + /*!< It must use values from tenuSubTypes. + */ + uint8 u8ServiceClass; + /*!< Service class from Wi-Fi header. + */ + uint8 u8Priority; + /*!< Priority from Wi-Fi header. + */ + uint8 u8HeaderLength; + /*!< Frame Header length. + */ + uint8 u8CipherType; + /*!< Encryption type for the rx packet. + */ + uint8 au8SrcMacAddress[6]; + /* ZERO means DO NOT FILTER Source address. + */ + uint8 au8DstMacAddress[6]; + /* ZERO means DO NOT FILTER Destination address. + */ + uint8 au8BSSID[6]; + /* ZERO means DO NOT FILTER BSSID. + */ + uint16 u16DataLength; + /*!< Data payload length (Header excluded). + */ + uint16 u16FrameLength; + /*!< Total frame length (Header + Data). + */ + uint32 u32DataRateKbps; + /*!< Data Rate in Kbps. + */ + sint8 s8RSSI; + /*!< RSSI. + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2MWifiRxPacketInfo; + + +/*! +@struct \ + tstrM2MWifiTxPacketInfo + +@brief Wi-Fi TX Packet Info + + The M2M Application has the ability to compose a RAW Wi-Fi frames (under the application responsibility). + When transmitting a Wi-Fi packet, the application must supply the firmware with this structure for sending the target frame. +*/ +typedef struct{ + uint16 u16PacketSize; + /*!< Wlan frame length. + */ + uint16 u16HeaderLength; + /*!< Wlan frame header length. + */ +}tstrM2MWifiTxPacketInfo; + + +/*! + @struct \ + tstrM2MP2PConnect + + @brief + Set the device to operate in the Wi-Fi Direct (P2P) mode. +*/ +typedef struct { + uint8 u8ListenChannel; + /*!< P2P Listen Channel (1, 6 or 11) + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2MP2PConnect; + +/*! +@struct \ + tstrM2MAPConfig + +@brief AP Configuration + + This structure holds the configuration parameters for the M2M AP mode. It should be set by the application when + it requests to enable the M2M AP operation mode. The M2M AP mode currently supports only WEP security (with + the NO Security option available of course). +*/ +typedef struct { + /*!< + Configuration parameters for the WiFi AP. + */ + uint8 au8SSID[M2M_MAX_SSID_LEN]; + /*!< AP SSID + */ + uint8 u8ListenChannel; + /*!< Wi-Fi RF Channel which the AP will operate on + */ + uint8 u8KeyIndx; + /*!< Wep key Index + */ + uint8 u8KeySz; + /*!< Wep key Size + */ + uint8 au8WepKey[WEP_104_KEY_STRING_SIZE + 1]; + /*!< Wep key + */ + uint8 u8SecType; + /*!< Security type: Open or WEP only in the current implementation + */ + uint8 u8SsidHide; + /*!< SSID Status "Hidden(1)/Visible(0)" + */ + uint8 au8DHCPServerIP[4]; + /*!< Ap IP server address + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing alignment + */ +}tstrM2MAPConfig; + + +/*! +@struct \ + tstrM2mServerInit + +@brief + PS Server initialization. +*/ +typedef struct { + uint8 u8Channel; + /*!< Server Listen channel + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mServerInit; + + +/*! +@struct \ + tstrM2mClientState + +@brief + PS Client State. +*/ +typedef struct { + uint8 u8State; + /*!< PS Client State + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mClientState; + + +/*! +@struct \ + tstrM2Mservercmd + +@brief + PS Server CMD +*/ +typedef struct { + uint8 u8cmd; + /*!< PS Server Cmd + */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2Mservercmd; + + +/*! +@struct \ + tstrM2mSetMacAddress + +@brief + Sets the MAC address from application. The WINC load the mac address from the effuse by default to the WINC configuration memory, + but that function is used to let the application overwrite the configuration memory with the mac address from the host. + +@note + It's recommended to call this only once before calling connect request and after the m2m_wifi_init +*/ +typedef struct { + uint8 au8Mac[6]; + /*!< MAC address array + */ + uint8 __PAD16__[2]; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2mSetMacAddress; + + +/*! +@struct \ + tstrM2MDeviceNameConfig + +@brief Device name + + It is assigned by the application. It is used mainly for Wi-Fi Direct device + discovery and WPS device information. +*/ +typedef struct { + uint8 au8DeviceName[M2M_DEVICE_NAME_MAX]; + /*!< NULL terminated device name + */ +}tstrM2MDeviceNameConfig; + + +/*! +@struct \ + tstrM2MIPConfig + +@brief + Static IP configuration. + +@note + All member IP addresses are expressed in Network Byte Order (eg. "192.168.10.1" will be expressed as 0x010AA8C0). + */ +typedef struct { + uint32 u32StaticIP; + /*!< The static IP assigned to the device. + */ + uint32 u32Gateway; + /*!< IP of the Default internet gateway. + */ + uint32 u32DNS; + /*!< IP for the DNS server. + */ + uint32 u32SubnetMask; + /*!< Subnet mask for the local area network. + */ +} tstrM2MIPConfig; + +/*! +@struct \ + tstrM2mIpRsvdPkt + +@brief + Received Packet Size and Data Offset + + */ +typedef struct{ + uint16 u16PktSz; + uint16 u16PktOffset; +} tstrM2mIpRsvdPkt; + + +/*! +@struct \ + tstrM2MProvisionModeConfig + +@brief + M2M Provisioning Mode Configuration + */ + +typedef struct { + tstrM2MAPConfig strApConfig; + /*!< + Configuration parameters for the WiFi AP. + */ + char acHttpServerDomainName[64]; + /*!< + The device domain name for HTTP provisioning. + */ + uint8 u8EnableRedirect; + /*!< + A flag to enable/disable HTTP redirect feature for the HTTP Provisioning server. If the Redirect is enabled, + all HTTP traffic (http://URL) from the device associated with WINC AP will be redirected to the HTTP Provisioning Web page. + - 0 : Disable HTTP Redirect. + - 1 : Enable HTTP Redirect. + */ + uint8 __PAD24__[3]; +}tstrM2MProvisionModeConfig; + + +/*! +@struct \ + tstrM2MProvisionInfo + +@brief + M2M Provisioning Information obtained from the HTTP Provisioning server. + */ +typedef struct{ + uint8 au8SSID[M2M_MAX_SSID_LEN]; + /*!< + Provisioned SSID. + */ + uint8 au8Password[M2M_MAX_PSK_LEN]; + /*!< + Provisioned Password. + */ + uint8 u8SecType; + /*!< + Wifi Security type. + */ + uint8 u8Status; + /*!< + Provisioning status. It must be checked before reading the provisioning information. It may be + - M2M_SUCCESS : Provision successful. + - M2M_FAIL : Provision Failed. + */ +}tstrM2MProvisionInfo; + + +/*! +@struct \ + tstrM2MConnInfo + +@brief + M2M Provisioning Information obtained from the HTTP Provisioning server. + */ +typedef struct{ + char acSSID[M2M_MAX_SSID_LEN]; + /*!< AP connection SSID name */ + uint8 u8SecType; + /*!< Security type */ + uint8 au8IPAddr[4]; + /*!< Connection IP address */ + uint8 au8MACAddress[6]; + /*!< MAC address of the peer Wi-Fi station */ + sint8 s8RSSI; + /*!< Connection RSSI signal */ + uint8 __PAD24__[3]; + /*!< Padding bytes for forcing 4-byte alignment */ +}tstrM2MConnInfo; + +/*! +@struct \ + tstrOtaInitHdr + +@brief + OTA Image Header + */ + +typedef struct{ + uint32 u32OtaMagicValue; + /*!< Magic value kept in the OTA image after the + sha256 Digest buffer to define the Start of OTA Header */ + uint32 u32OtaPayloadSzie; + /*!< + The Total OTA image payload size, include the sha256 key size + */ + +}tstrOtaInitHdr; + +/*! +@struct \ + tstrOtaControlSec + +@brief + Control section structure is used to define the working image and + the validity of the roll-back image and its offset, also both firmware versions is kept in that structure. + */ + +typedef struct { + uint32 u32OtaMagicValue; +/*!< + Magic value used to ensure the structure is valid or not +*/ + uint32 u32OtaFormatVersion; +/*!< + NA NA NA Flash version cs struct version + 00 00 00 00 00 + Control structure format version, the value will be incremented in case of structure changed or updated +*/ + uint32 u32OtaSequenceNumber; +/*!< + Sequence number is used while update the control structure to keep track of how many times that section updated +*/ + uint32 u32OtaLastCheckTime; +/*!< + Last time OTA check for update +*/ + uint32 u32OtaCurrentworkingImagOffset; +/*!< + Current working offset in flash +*/ + uint32 u32OtaCurrentworkingImagFirmwareVer; +/*!< + current working image version ex 18.0.1 +*/ + uint32 u32OtaRollbackImageOffset; +/*!< + Roll-back image offset in flash +*/ + uint32 u32OtaRollbackImageValidStatus; +/*!< + roll-back image valid status +*/ + uint32 u32OtaRollbackImagFirmwareVer; +/*!< + Roll-back image version (ex 18.0.3) +*/ + uint32 u32OtaCortusAppWorkingOffset; +/*!< + cortus app working offset in flash +*/ + uint32 u32OtaCortusAppWorkingValidSts; +/*!< + Working Cortus app valid status +*/ + uint32 u32OtaCortusAppWorkingVer; +/*!< + Working cortus app version (ex 18.0.3) +*/ + uint32 u32OtaCortusAppRollbackOffset; +/*!< + cortus app rollback offset in flash +*/ + uint32 u32OtaCortusAppRollbackValidSts; +/*!< + roll-back cortus app valid status +*/ + uint32 u32OtaCortusAppRollbackVer; +/*!< + Roll-back cortus app version (ex 18.0.3) +*/ + uint32 u32OtaControlSecCrc; +/*!< + CRC for the control structure to ensure validity +*/ +} tstrOtaControlSec; + +/*! +@enum \ + tenuOtaUpdateStatus + +@brief + OTA return status +*/ +typedef enum { + OTA_STATUS_SUCSESS = 0, + /*!< OTA Success with not errors. */ + OTA_STATUS_FAIL = 1, + /*!< OTA generic fail. */ + OTA_STATUS_INVAILD_ARG = 2, + /*!< Invalid or malformed download URL. */ + OTA_STATUS_INVAILD_RB_IMAGE = 3, + /*!< Invalid rollback image. */ + OTA_STATUS_INVAILD_FLASH_SIZE = 4, + /*!< Flash size on device is not enough for OTA. */ + OTA_STATUS_AlREADY_ENABLED = 5, + /*!< An OTA operation is already enabled. */ + OTA_STATUS_UPDATE_INPROGRESS = 6, + /*!< An OTA operation update is in progress */ + OTA_STATUS_IMAGE_VERIF_FAILED = 7, + /*!< OTA Verfication failed */ + OTA_STATUS_CONNECTION_ERROR = 8, + /*!< OTA connection error */ + OTA_STATUS_SERVER_ERROR = 9, + /*!< OTA server Error (file not found or else ...) */ +} tenuOtaUpdateStatus; +/*! +@enum \ + tenuOtaUpdateStatusType + +@brief + OTA update Status type +*/ +typedef enum { + + DL_STATUS = 1, + /*!< Download OTA file status + */ + SW_STATUS = 2, + /*!< Switching to the upgrade firmware status + */ + RB_STATUS = 3, + /*!< Roll-back status + */ +}tenuOtaUpdateStatusType; + + +/*! +@struct \ + tstrOtaUpdateStatusResp + +@brief + OTA Update Information + +@sa + tenuWPSTrigger +*/ +typedef struct { + uint8 u8OtaUpdateStatusType; + /*!< + Status type tenuOtaUpdateStatusType + */ + uint8 u8OtaUpdateStatus; + /*!< + OTA_SUCCESS + OTA_ERR_WORKING_IMAGE_LOAD_FAIL + OTA_ERR_INVAILD_CONTROL_SEC + M2M_ERR_OTA_SWITCH_FAIL + M2M_ERR_OTA_START_UPDATE_FAIL + M2M_ERR_OTA_ROLLBACK_FAIL + M2M_ERR_OTA_INVAILD_FLASH_SIZE + M2M_ERR_OTA_INVAILD_ARG + */ + uint8 _PAD16_[2]; +}tstrOtaUpdateStatusResp; + +/*! +@struct \ + tstrOtaUpdateInfo + +@brief + OTA Update Information + +@sa + tenuWPSTrigger +*/ +typedef struct { + uint32 u8NcfUpgradeVersion; + /*!< NCF OTA Upgrade Version + */ + uint32 u8NcfCurrentVersion; + /*!< NCF OTA Current firmware version + */ + uint32 u8NcdUpgradeVersion; + /*!< NCD (host) upgraded version (if the u8NcdRequiredUpgrade == true) + */ + uint8 u8NcdRequiredUpgrade; + /*!< NCD Required upgrade to the above version + */ + uint8 u8DownloadUrlOffset; + /*!< Download URL offset in the received packet + */ + uint8 u8DownloadUrlSize; + /*!< Download URL size in the received packet + */ + uint8 __PAD8__; + /*!< Padding bytes for forcing 4-byte alignment + */ +} tstrOtaUpdateInfo; + +/*! +@struct \ + tstrSystemTime + +@brief + Used for time storage. +*/ +typedef struct{ + uint16 u16Year; + uint8 u8Month; + uint8 u8Day; + uint8 u8Hour; + uint8 u8Minute; + uint8 u8Second; +}tstrSystemTime; + +/*! +@struct \ + tstrM2MMulticastMac + +@brief + M2M add/remove multi-cast mac address + */ + typedef struct { + uint8 au8macaddress[M2M_MAC_ADDRES_LEN]; + /*!< + Mac address needed to be added or removed from filter. + */ + uint8 u8AddRemove; + /*!< + set by 1 to add or 0 to remove from filter. + */ + uint8 __PAD8__; + /*!< Padding bytes for forcing 4-byte alignment + */ +}tstrM2MMulticastMac; + +/*! +@struct \ + tstrPrng + +@brief + M2M Request PRNG + */ + typedef struct { + /*!< + return buffer address + */ + uint8 *pu8RngBuff; + /*!< + PRNG size requested + */ + uint16 u16PrngSize; + /*!< + PRNG pads + */ + uint8 __PAD16__[2]; +}tstrPrng; + + + /**@}*/ + +#endif diff --git a/ext/drivers/atmel/winc1500/driver/include/m2m_wifi.h b/ext/drivers/atmel/winc1500/driver/include/m2m_wifi.h new file mode 100755 index 0000000000000..778eb8fd7189a --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/include/m2m_wifi.h @@ -0,0 +1,2578 @@ +/** + * + * \file + * + * \brief WINC WLAN Application Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef __M2M_WIFI_H__ +#define __M2M_WIFI_H__ + +/** \defgroup m2m_wifi WLAN + * + */ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "common/include/nm_common.h" +#include "driver/include/m2m_types.h" +#include "driver/source/nmdrv.h" + +#ifdef CONF_MGMT + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/**@defgroup WlanEnums Enumerations and Typedefs + * @ingroup m2m_wifi + * @{*/ +/*! +@enum \ + tenuWifiFrameType + +@brief + Enumeration for Wi-Fi MAC frame type codes (2-bit) + The following types are used to identify the type of frame sent or received. + Each frame type constitutes a number of frame subtypes as defined in @ref tenuSubTypes to specify the exact type of frame. + Values are defined as per the IEEE 802.11 standard. + +@remarks + The following frame types are useful for advanced user usage when @ref CONF_MGMT is defined + and the user application requires to monitor the frame transmission and reception. +@see + tenuSubTypes +*/ +typedef enum { + MANAGEMENT = 0x00, + /*!< Wi-Fi Management frame (Probe Req/Resp, Beacon, Association Req/Resp ...etc). + */ + CONTROL = 0x04, + /*!< Wi-Fi Control frame (eg. ACK frame). + */ + DATA_BASICTYPE = 0x08, + /*!< Wi-Fi Data frame. + */ + RESERVED = 0x0C, + + M2M_WIFI_FRAME_TYPE_ANY = 0xFF +/*!< Set monitor mode to receive any of the frames types +*/ +}tenuWifiFrameType; + + +/*! +@enum \ + tenuSubTypes + +@brief + Enumeration for Wi-Fi MAC Frame subtype code (6-bit). + The frame subtypes fall into one of the three frame type groups as defined in @ref tenuWifiFrameType + (MANAGEMENT, CONTROL & DATA). + Values are defined as per the IEEE 802.11 standard. +@remarks + The following sub-frame types are useful for advanced user usage when @ref CONF_MGMT is defined + and the application developer requires to monitor the frame transmission and reception. +@see + tenuWifiFrameType +*/ +typedef enum { + /*!< Sub-Types related to Management Sub-Types */ + ASSOC_REQ = 0x00, + ASSOC_RSP = 0x10, + REASSOC_REQ = 0x20, + REASSOC_RSP = 0x30, + PROBE_REQ = 0x40, + PROBE_RSP = 0x50, + BEACON = 0x80, + ATIM = 0x90, + DISASOC = 0xA0, + AUTH = 0xB0, + DEAUTH = 0xC0, + ACTION = 0xD0, +/**@{*/ + /* Sub-Types related to Control */ + PS_POLL = 0xA4, + RTS = 0xB4, + CTS = 0xC4, + ACK = 0xD4, + CFEND = 0xE4, + CFEND_ACK = 0xF4, + BLOCKACK_REQ = 0x84, + BLOCKACK = 0x94, +/**@{*/ + /* Sub-Types related to Data */ + DATA = 0x08, + DATA_ACK = 0x18, + DATA_POLL = 0x28, + DATA_POLL_ACK = 0x38, + NULL_FRAME = 0x48, + CFACK = 0x58, + CFPOLL = 0x68, + CFPOLL_ACK = 0x78, + QOS_DATA = 0x88, + QOS_DATA_ACK = 0x98, + QOS_DATA_POLL = 0xA8, + QOS_DATA_POLL_ACK = 0xB8, + QOS_NULL_FRAME = 0xC8, + QOS_CFPOLL = 0xE8, + QOS_CFPOLL_ACK = 0xF8, + M2M_WIFI_FRAME_SUB_TYPE_ANY = 0xFF + /*!< Set monitor mode to receive any of the frames types + */ +}tenuSubTypes; + + +/*! +@enum \ + tenuInfoElementId + +@brief + Enumeration for the Wi-Fi Information Element(IE) IDs, which indicates the specific type of IEs. + IEs are management frame information included in management frames. + Values are defined as per the IEEE 802.11 standard. + +@details Available IDs are:- + + ISSID : Service Set Identifier (SSID) + + ISUPRATES : Supported Rates + + IFHPARMS : FH parameter set + + IDSPARMS : DS parameter set + + ICFPARMS : CF parameter set + + ITIM : Traffic Information Map + + IIBPARMS : IBSS parameter set + + ICOUNTRY : Country element. + + IEDCAPARAMS : EDCA parameter set + + ITSPEC : Traffic Specification + + ITCLAS : Traffic Classification + + ISCHED : Schedule. + + ICTEXT : Challenge Text + + IPOWERCONSTRAINT : Power Constraint. + + IPOWERCAPABILITY : Power Capability + + ITPCREQUEST : TPC Request + + ITPCREPORT : TPC Report + + ISUPCHANNEL : Supported channel list + + ICHSWANNOUNC : Channel Switch Announcement + + IMEASUREMENTREQUEST : Measurement request + + IMEASUREMENTREPORT : Measurement report + + IQUIET : Quiet element Info + + IIBSSDFS : IBSS DFS + + IERPINFO : ERP Information + + ITSDELAY : TS Delay + + ITCLASPROCESS : TCLAS Processing + + IHTCAP : HT Capabilities + + IQOSCAP : QoS Capability + + IRSNELEMENT : RSN Information Element + + IEXSUPRATES : Extended Supported Rates + + IEXCHSWANNOUNC : Extended Ch Switch Announcement + + IHTOPERATION : HT Information + + ISECCHOFF : Secondary Channel Offset + + I2040COEX : Coexistence IE + + I2040INTOLCHREPORT : Intolerant channel report + + IOBSSSCAN : OBSS Scan parameters + + IEXTCAP : Extended capability + + IWMM : WMM parameters + + IWPAELEMENT : WPA Information Element + +*/ +typedef enum { + ISSID = 0, + /*!< Service Set Identifier (SSID) + */ + ISUPRATES = 1, + /*!< Supported Rates + */ + IFHPARMS = 2, + /*!< FH parameter set + */ + IDSPARMS = 3, + /*!< DS parameter set + */ + ICFPARMS = 4, + /*!< CF parameter set + */ + ITIM = 5, + /*!< Traffic Information Map + */ + IIBPARMS = 6, + /*!< IBSS parameter set + */ + ICOUNTRY = 7, + /*!< Country element. + */ + IEDCAPARAMS = 12, + /*!< EDCA parameter set + */ + ITSPEC = 13, + /*!< Traffic Specification + */ + ITCLAS = 14, + /*!< Traffic Classification + */ + ISCHED = 15, + /*!< Schedule. + */ + ICTEXT = 16, + /*!< Challenge Text + */ + IPOWERCONSTRAINT = 32, + /*!< Power Constraint. + */ + IPOWERCAPABILITY = 33, + /*!< Power Capability + */ + ITPCREQUEST = 34, + /*!< TPC Request + */ + ITPCREPORT = 35, + /*!< TPC Report + */ + ISUPCHANNEL = 36, + /* Supported channel list + */ + ICHSWANNOUNC = 37, + /*!< Channel Switch Announcement + */ + IMEASUREMENTREQUEST = 38, + /*!< Measurement request + */ + IMEASUREMENTREPORT = 39, + /*!< Measurement report + */ + IQUIET = 40, + /*!< Quiet element Info + */ + IIBSSDFS = 41, + /*!< IBSS DFS + */ + IERPINFO = 42, + /*!< ERP Information + */ + ITSDELAY = 43, + /*!< TS Delay + */ + ITCLASPROCESS = 44, + /*!< TCLAS Processing + */ + IHTCAP = 45, + /*!< HT Capabilities + */ + IQOSCAP = 46, + /*!< QoS Capability + */ + IRSNELEMENT = 48, + /*!< RSN Information Element + */ + IEXSUPRATES = 50, + /*!< Extended Supported Rates + */ + IEXCHSWANNOUNC = 60, + /*!< Extended Ch Switch Announcement + */ + IHTOPERATION = 61, + /*!< HT Information + */ + ISECCHOFF = 62, + /*!< Secondary Channel Offset + */ + I2040COEX = 72, + /*!< 20/40 Coexistence IE + */ + I2040INTOLCHREPORT = 73, + /*!< 20/40 Intolerant channel report + */ + IOBSSSCAN = 74, + /*!< OBSS Scan parameters + */ + IEXTCAP = 127, + /*!< Extended capability + */ + IWMM = 221, + /*!< WMM parameters + */ + IWPAELEMENT = 221 + /*!< WPA Information Element + */ +}tenuInfoElementId; + //@} + +/*! +@struct \ + tenuWifiCapability + +@brief + Enumeration for capability Information field bit. + The value of the capability information field from the 802.11 management frames received by the wireless LAN interface. + Defining the capabilities of the Wi-Fi system. Values are defined as per the IEEE 802.11 standard. + +@details + Capabilities:- + ESS/IBSS : Defines whether a frame is coming from an AP or not. + POLLABLE : CF Poll-able + POLLREQ : Request to be polled + PRIVACY : WEP encryption supported + SHORTPREAMBLE : Short Preamble is supported + SHORTSLOT : Short Slot is supported + PBCC :PBCC + CHANNELAGILITY :Channel Agility + SPECTRUM_MGMT :Spectrum Management + DSSS_OFDM : DSSS-OFDM +*/ +typedef enum{ + ESS = 0x01, + /*!< ESS capability + */ + IBSS = 0x02, + /*!< IBSS mode + */ + POLLABLE = 0x04, + /*!< CF Pollable + */ + POLLREQ = 0x08, + /*!< Request to be polled + */ + PRIVACY = 0x10, + /*!< WEP encryption supported + */ + SHORTPREAMBLE = 0x20, + /*!< Short Preamble is supported + */ + SHORTSLOT = 0x400, + /*!< Short Slot is supported + */ + PBCC = 0x40, + /*!< PBCC + */ + CHANNELAGILITY = 0x80, + /*!< Channel Agility + */ + SPECTRUM_MGMT = 0x100, + /*!< Spectrum Management + */ + DSSS_OFDM = 0x2000 + /*!< DSSS-OFDM + */ +}tenuWifiCapability; + + +#endif + +/*! +@typedef \ + tpfAppWifiCb + +@brief + Wi-Fi's main callback function handler, for handling the M2M_WIFI events received on the Wi-Fi interface. + Such notifications are received in response to Wi-Fi/P2P operations such as @ref m2m_wifi_request_scan, + @ref m2m_wifi_connect. + Wi-Fi/P2P operations are implemented in an asynchronous mode, and all incoming information/status + are to be handled through this callback function when the corresponding notification is received. + Applications are expected to assign this wi-fi callback function by calling @ref m2m_wifi_init +@param [in] u8MsgType + Type of notification. Possible types are: + /ref M2M_WIFI_RESP_CON_STATE_CHANGED + /ref M2M_WIFI_RESP_CONN_INFO + /ref M2M_WIFI_REQ_DHCP_CONF + /ref M2M_WIFI_REQ_WPS + /ref M2M_WIFI_RESP_IP_CONFLICT + /ref M2M_WIFI_RESP_SCAN_DONE + /ref M2M_WIFI_RESP_SCAN_RESULT + /ref M2M_WIFI_RESP_CURRENT_RSSI + /ref M2M_WIFI_RESP_CLIENT_INFO + /ref M2M_WIFI_RESP_PROVISION_INFO + /ref M2M_WIFI_RESP_DEFAULT_CONNECT + + In case Bypass mode is defined : + @ref M2M_WIFI_RESP_ETHERNET_RX_PACKET + + In case Monitoring mode is used: + @ref M2M_WIFI_RESP_WIFI_RX_PACKET + +@param [in] pvMsg + A pointer to a buffer containing the notification parameters (if any). It should be + Casted to the correct data type corresponding to the notification type. + +@see + tstrM2mWifiStateChanged + tstrM2MWPSInfo + tstrM2mScanDone + tstrM2mWifiscanResult +*/ +typedef void (*tpfAppWifiCb) (uint8 u8MsgType, void * pvMsg); + +/*! +@typedef \ + tpfAppEthCb + +@brief + Ethernet (Bypass mode) notification callback function receiving Bypass mode events as defined in + the Wi-Fi responses enumeration @ref tenuM2mStaCmd. + +@param [in] u8MsgType + Type of notification. Possible types are: + - [M2M_WIFI_RESP_ETHERNET_RX_PACKET](@ref M2M_WIFI_RESP_ETHERNET_RX_PACKET) + +@param [in] pvMsg + A pointer to a buffer containing the notification parameters (if any). It should be + casted to the correct data type corresponding to the notification type. + For example, it could be a pointer to the buffer holding the received frame in case of @ref M2M_WIFI_RESP_ETHERNET_RX_PACKET + event. + +@param [in] pvControlBuf + A pointer to control buffer describing the accompanied message. + To be casted to @ref tstrM2mIpCtrlBuf in case of @ref M2M_WIFI_RESP_ETHERNET_RX_PACKET event. + +@warning + Make sure that the bypass mode is defined before using @ref tpfAppEthCb. + +@see + m2m_wifi_init + +*/ +typedef void (*tpfAppEthCb) (uint8 u8MsgType, void * pvMsg,void * pvCtrlBuf); + +/*! +@typedef \ + tpfAppMonCb + +@brief + Wi-Fi monitoring mode callback function. This function delivers all received wi-Fi packets through the Wi-Fi interface. + Applications requiring to operate in the monitoring should call the asynchronous function m2m_wifi_enable_monitoring_mode + and expect to receive the Wi-Fi packets through this callback function, when the event ....is received. + To disable the monitoring mode a call to @ref m2m_wifi_disable_monitoring_mode should be made. +@param [in] pstrWifiRxPacket + Pointer to a structure holding the Wi-Fi packet header parameters. + +@param [in] pu8Payload + Pointer to the buffer holding the Wi-Fi packet payload information required by the application starting from the + defined OFFSET by the application (when calling m2m_wifi_enable_monitoring_mode). + Could hold a value of NULL, if the application does not need any data from the payload. + +@param [in] u16PayloadSize + The size of the payload in bytes. + +@see + m2m_wifi_enable_monitoring_mode + +@warning + u16PayloadSize should not exceed the buffer size given through m2m_wifi_enable_monitoring_mode. + +*/ +typedef void (*tpfAppMonCb) (tstrM2MWifiRxPacketInfo *pstrWifiRxPacket, uint8 * pu8Payload, uint16 u16PayloadSize); + +/** +@struct \ + tstrEthInitParam + +@brief + Structure to hold Ethernet interface parameters. + Structure is to be defined and have its attributes set,based on the application's functionality before + a call is made to the initialize the wi-fi operations by calling the @ref m2m_wifi_init function. + Part of the wi-fi configuration structure @ref tstrWifiInitParam. + Applications shouldn't need to define this structure, if the bypass mode is not defined. + +@see + tpfAppEthCb + tpfAppWifiCb + m2m_wifi_init + +@warning + Make sure that bypass mode is defined before using @ref tstrEthInitParam. + +*/ +typedef struct { + tpfAppWifiCb pfAppWifiCb; + /*!< + Callback for wifi notifications. + */ + tpfAppEthCb pfAppEthCb; + /*!< + Callback for Ethernet interface. + */ + uint8 * au8ethRcvBuf; + /*!< + Pointer to Receive Buffer of Ethernet Packet + */ + uint16 u16ethRcvBufSize; + /*!< + Size of Receive Buffer for Ethernet Packet + */ + uint8 u8EthernetEnable; + /*!< + Enable Ethernet mode flag + */ + uint8 __PAD8__; + +} tstrEthInitParam; +/*! +@struct \ + tstrM2mIpCtrlBuf + +@brief + Structure holding the incoming buffer's data size information, indicating the data size of the buffer and the remaining buffer's data size . + The data of the buffer which holds the packet sent to the host when in the bypass mode, is placed in the @ref tstrEthInitParam structure in the + @ref au8ethRcvBuf attribute. This following information is retrieved in the host when an event @ref M2M_WIFI_RESP_ETHERNET_RX_PACKET is received in + the Wi-Fi callback function @ref tpfAppWifiCb. + + The application is expected to use this structure's information to determine if there is still incoming data to be received from the firmware. + + + @see + tpfAppEthCb + tstrEthInitParam + + @warning + Make sure that bypass mode is defined before using @ref tstrM2mIpCtrlBuf + + */ +typedef struct{ + uint16 u16DataSize; + /*!< + Size of the received data in bytes. + */ + uint16 u16RemainigDataSize; + /*!< + Size of the remaining data bytes to be delivered to host. + */ +} tstrM2mIpCtrlBuf; + + +/** +@struct \ + tstrWifiInitParam + +@brief + Structure, holding the Wi-fi configuration attributes such as the wi-fi callback , monitoring mode callback and Ethernet parameter initialization structure. + Such configuration parameters are required to be set before calling the wi-fi initialization function @ref m2m_wifi_init. + @ref pfAppWifiCb attribute must be set to handle the wi-fi callback operations. + @ref pfAppMonCb attribute, is optional based on whether the application requires the monitoring mode configuration, and can there not + be set before the initialization. + @ref strEthInitParam structure, is another optional configuration based on whether the bypass mode is set. + +*/ +typedef struct { + tpfAppWifiCb pfAppWifiCb; + /*!< + Callback for Wi-Fi notifications. + */ + tpfAppMonCb pfAppMonCb; + /*!< + Callback for monitoring interface. + */ + tstrEthInitParam strEthInitParam ; + /*!< + Structure to hold Ethernet interface parameters. + */ + +} tstrWifiInitParam; + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/** \defgroup WLANAPI Function + * @ingroup m2m_wifi + */ +#ifdef __cplusplus + extern "C" { +#endif + /** @defgroup WiFiDownloadFn m2m_wifi_download_mode + * @ingroup WLANAPI + * Synchronous download mode entry function that prepares the WINC board to enter the download mode, ready for the firmware or certificate download. +* The WINC board is prepared for download, through initializations for the WINC driver including bus initializations and interrupt enabling, it also halts the chip, to allow for the firmware downloads. +* Firmware can be downloaded through a number of interfaces, UART, I2C and SPI. + */ + /**@{*/ +/*! +@fn \ + NMI_API void m2m_wifi_download_mode(void); + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_download_mode(void); + /**@}*/ + /** @defgroup WifiInitFn m2m_wifi_init + * @ingroup WLANAPI + * Synchronous initialization function for the WINC driver. This function initializes the driver by, registering the call back function for M2M_WIFI layer(also the call back function for bypass mode/monitoring mode if defined), + * initializing the host interface layer and the bus interfaces. + * Wi-Fi callback registering is essential to allow the handling of the events received, in response to the asynchronous Wi-Fi operations. + +Following are the possible Wi-Fi events that are expected to be received through the call back function(provided by the application) to the M2M_WIFI layer are : + + @ref M2M_WIFI_RESP_CON_STATE_CHANGED \n + @ref M2M_WIFI_RESP_CONN_INFO \n + @ref M2M_WIFI_REQ_DHCP_CONF \n + @ref M2M_WIFI_REQ_WPS \n + @ref M2M_WIFI_RESP_IP_CONFLICT \n + @ref M2M_WIFI_RESP_SCAN_DONE \n + @ref M2M_WIFI_RESP_SCAN_RESULT \n + @ref M2M_WIFI_RESP_CURRENT_RSSI \n + @ref M2M_WIFI_RESP_CLIENT_INFO \n + @ref M2M_WIFI_RESP_PROVISION_INFO \n + @ref M2M_WIFI_RESP_DEFAULT_CONNECT \n + Example: \n + In case Bypass mode is defined : \n + @ref M2M_WIFI_RESP_ETHERNET_RX_PACKET + + In case Monitoring mode is used: \n + @ref M2M_WIFI_RESP_WIFI_RX_PACKET + + Any application using the WINC driver must call this function at the start of its main function. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_init(tstrWifiInitParam * pWifiInitParam); + +@param [in] pWifiInitParam + This is a pointer to the @ref tstrWifiInitParam structure which holds the pointer to the application WIFI layer call back function, + monitoring mode call back and @ref tstrEthInitParam structure containing bypass mode parameters. + +@pre + Prior to this function call, application users must provide a call back function responsible for receiving all the wi-fi events that are received on the M2M_WIFI layer. + +@warning + Failure to successfully complete function indicates that the driver couldn't be initialized and a fatal error will prevent the application from proceeding. + +@see + m2m_wifi_deinit + tenuM2mStaCmd + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_init(tstrWifiInitParam * pWifiInitParam); + /**@}*/ + /** @defgroup WifiDeinitFn m2m_wifi_deinit + * @ingroup WLANAPI + * Synchronous de-initialization function to the WINC1500 driver. De-initializes the host interface and frees any resources used by the M2M_WIFI layer. + * This function must be called in the application closing phase,to ensure that all resources have been correctly released. No arguments are expected to be passed in. + */ +/**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_deinit(void * arg); + +@param [in] arg + Generic argument. Not used in current implementation. +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_deinit(void * arg); + /**@}*/ +/** @defgroup WifiHandleEventsFn m2m_wifi_handle_events +* @ingroup WLANAPI +* Synchronous M2M event handler function, responsible for handling interrupts received from the WINC firmware. +* Application developers should call this function periodically in-order to receive the events that are to be handled by the +* callback functions implemented by the application. + + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_handle_events(void * arg); + +@pre + Prior to receiving wi-fi interrupts, the WINC driver should have been successfully initialized by calling the @ref m2m_wifi_init function. + +@warning + Failure to successfully complete this function indicates bus errors and hence a fatal error that will prevent the application from proceeding. + +@return + The function returns @ref M2M_SUCCESS for successful interrupt handling and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_handle_events(void * arg); + /**@}*/ +/** @defgroup WifiDefaultConnectFn m2m_wifi_default_connect + * @ingroup WLANAPI + * Asynchronous Wi-Fi connection function. An application calling this function will cause the firmware to correspondingly connect to the last successfully connected AP from the cached connections. + * A failure to connect will result in a response of @ref M2M_WIFI_RESP_DEFAULT_CONNECT indicating the connection error as defined in the structure @ref tstrM2MDefaultConnResp. + * Possible errors are: + * The connection list is empty @ref M2M_DEFAULT_CONN_EMPTY_LIST or a mismatch for the saved AP name @ref M2M_DEFAULT_CONN_SCAN_MISMATCH. + * only difference between this function and @ref m2m_wifi_connect, is the connection parameters. + * Connection using this function is expected to connect to cached connection parameters. + + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_default_connect(void); + +@pre + Prior to connecting, the WINC driver should have been successfully initialized by calling the @ref m2m_wifi_init function. + +@warning + This function must be called in station mode only. + It's important to note that successful completion of a call to m2m_wifi_default_connect() does not guarantee success of the WIFI connection, + and a negative return value indicates only locally-detected errors. + +@see + m2m_wifi_connect + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_default_connect(void); + /**@}*/ +/** @defgroup WifiConnectFn m2m_wifi_connect + * @ingroup WLANAPI + * Asynchronous wi-fi connection function to a specific AP. Prior to a successful connection, the application developers must know the SSID of the AP, the security type, + * the authentication information parameters and the channel number to which the connection will be established. + * The connection status is known when a response of @ref M2M_WIFI_RESP_CON_STATE_CHANGED is received based on the states defined in @ref tenuM2mConnState, + * successful connection is defined by @ref M2M_WIFI_CONNECTED +* + * The only difference between this function and @ref m2m_wifi_default_connect, is the connection parameters. + * Connection using this function is expected to be made to a specific AP and to a specified channel. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_connect(char *pcSsid, uint8 u8SsidLen, uint8 u8SecType, void *pvAuthInfo, uint16 u16Ch); + +@param [in] pcSsid + A buffer holding the SSID corresponding to the requested AP. + +@param [in] u8SsidLen + Length of the given SSID (not including the NULL termination). + A length less than ZERO or greater than the maximum defined SSID @ref M2M_MAX_SSID_LEN will result in a negative error + @ref M2M_ERR_FAIL. + +@param [in] u8SecType + Wi-Fi security type security for the network. It can be one of the following types: + -@ref M2M_WIFI_SEC_OPEN + -@ref M2M_WIFI_SEC_WEP + -@ref M2M_WIFI_SEC_WPA_PSK + -@ref M2M_WIFI_SEC_802_1X + A value outside these possible values will result in a negative return error @ref M2M_ERR_FAIL. + +@param [in] pvAuthInfo + Authentication parameters required for completing the connection. It is type is based on the Security type. + If the authentication parameters are NULL or are greater than the maximum length of the authentication parameters length as defined by + @ref M2M_MAX_PSK_LEN a negative error will return @ref M2M_ERR_FAIL(-12) indicating connection failure. + +@param [in] u16Ch + Wi-Fi channel number as defined in @ref tenuM2mScanCh enumeration. + Channel number greater than @ref M2M_WIFI_CH_14 returns a negative error @ref M2M_ERR_FAIL(-12). + Except if the value is M2M_WIFI_CH_ALL(255), since this indicates that the firmware should scan all channels to find the SSID requested to connect to. + Failure to find the connection match will return a negative error @ref M2M_DEFAULT_CONN_SCAN_MISMATCH. +@pre + Prior to a successful connection request, the wi-fi driver must have been successfully initialized through the call of the @ref @m2m_wifi_init function +@see + tuniM2MWifiAuth + tstr1xAuthCredentials + tstrM2mWifiWepParams + +@warning + -This function must be called in station mode only. + -Successful completion of this function does not guarantee success of the WIFI connection, and + a negative return value indicates only locally-detected errors. + +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_connect(char *pcSsid, uint8 u8SsidLen, uint8 u8SecType, void *pvAuthInfo, uint16 u16Ch); + /**@}*/ +/** @defgroup WifiConnectFn m2m_wifi_connect_sc + * @ingroup WLANAPI + * Asynchronous wi-fi connection function to a specific AP. Prior to a successful connection, the application developers must know the SSID of the AP, the security type, + * the authentication information parameters and the channel number to which the connection will be established.this API allows the user to choose + * whether to + * The connection status is known when a response of @ref M2M_WIFI_RESP_CON_STATE_CHANGED is received based on the states defined in @ref tenuM2mConnState, + * successful connection is defined by @ref M2M_WIFI_CONNECTED + * The only difference between this function and @ref m2m_wifi_connect, is the option to save the acess point info ( SSID, password...etc) or not. + * Connection using this function is expected to be made to a specific AP and to a specified channel. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_connect_sc(char *pcSsid, uint8 u8SsidLen, uint8 u8SecType, void *pvAuthInfo, uint16 u16Ch,uint8 u8SaveCred); + +@param [in] pcSsid + A buffer holding the SSID corresponding to the requested AP. + +@param [in] u8SsidLen + Length of the given SSID (not including the NULL termination). + A length less than ZERO or greater than the maximum defined SSID @ref M2M_MAX_SSID_LEN will result in a negative error + @ref M2M_ERR_FAIL. + +@param [in] u8SecType + Wi-Fi security type security for the network. It can be one of the following types: + -@ref M2M_WIFI_SEC_OPEN + -@ref M2M_WIFI_SEC_WEP + -@ref M2M_WIFI_SEC_WPA_PSK + -@ref M2M_WIFI_SEC_802_1X + A value outside these possible values will result in a negative return error @ref M2M_ERR_FAIL. + +@param [in] pvAuthInfo + Authentication parameters required for completing the connection. It is type is based on the Security type. + If the authentication parameters are NULL or are greater than the maximum length of the authentication parameters length as defined by + @ref M2M_MAX_PSK_LEN a negative error will return @ref M2M_ERR_FAIL(-12) indicating connection failure. + +@param [in] u16Ch + Wi-Fi channel number as defined in @ref tenuM2mScanCh enumeration. + Channel number greater than @ref M2M_WIFI_CH_14 returns a negative error @ref M2M_ERR_FAIL(-12). + Except if the value is M2M_WIFI_CH_ALL(255), since this indicates that the firmware should scan all channels to find the SSID requested to connect to. + Failure to find the connection match will return a negative error @ref M2M_DEFAULT_CONN_SCAN_MISMATCH. + +@param [in] u8NoSaveCred + Option to store the acess point SSID and password into the WINC flash memory or not. + +@pre + Prior to a successful connection request, the wi-fi driver must have been successfully initialized through the call of the @ref @m2m_wifi_init function +@see + tuniM2MWifiAuth + tstr1xAuthCredentials + tstrM2mWifiWepParams + +@warning + -This function must be called in station mode only. + -Successful completion of this function does not guarantee success of the WIFI connection, and + a negative return value indicates only locally-detected errors. + +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ + NMI_API sint8 m2m_wifi_connect_sc(char *pcSsid, uint8 u8SsidLen, uint8 u8SecType, void *pvAuthInfo, uint16 u16Ch, uint8 u8SaveCred); + /**@}*/ +/** @defgroup WifiDisconnectFn m2m_wifi_disconnect + * @ingroup WLANAPI + * Synchronous wi-fi disconnection function, requesting a Wi-Fi disconnect from the currently connected AP. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_disconnect(void); + +@pre + Disconnection must be made to a successfully connected AP. If the WINC is not in the connected state, a call to this function will hold insignificant. + +@warning + This function must be called in station mode only. + +@see + m2m_wifi_connect + m2m_wifi_default_connect + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_disconnect(void); + /**@}*/ +/** @defgroup StartProvisionModeFn m2m_wifi_start_provision_mode + * @ingroup WLANAPI + * Asynchronous wi-fi provisioning function, which starts the WINC HTTP PROVISIONING mode. + The function triggers the WINC to activate the Wi-Fi AP (HOTSPOT) mode with the passed configuration parameters and then starts the + HTTP Provision WEB Server. + The provisioning status is returned in an event @ref M2M_WIFI_RESP_PROVISION_INFO + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_start_provision_mode(tstrM2MAPConfig *pstrAPConfig, char *pcHttpServerDomainName, uint8 bEnableHttpRedirect); + +@param [in] pstrAPConfig + AP configuration parameters as defined in @ref tstrM2MAPConfig configuration structure. + A NULL value passed in, will result in a negative error @ref M2M_ERR_FAIL. + +@param [in] pcHttpServerDomainName + Domain name of the HTTP Provision WEB server which others will use to load the provisioning Home page. + For example "wincconf.net". + +@param [in] bEnableHttpRedirect + A flag to enable/disable the HTTP redirect feature. Possible values are: + - ZERO DO NOT Use HTTP Redirect. In this case the associated device could open the provisioning page ONLY when + the HTTP Provision URL of the WINC HTTP Server is correctly written on the browser. + - Non-Zero value Use HTTP Redirect. In this case, all http traffic (http://URL) from the associated + device (Phone, PC, ...etc) will be redirected to the WINC HTTP Provisioning Home page. + +@pre + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at startup. Registering the callback + is done through passing it to the initialization @ref m2m_wifi_init function. + - The event @ref M2M_WIFI_RESP_CONN_INFO must be handled in the callback to receive the requested connection info. + +@see + tpfAppWifiCb + m2m_wifi_init + M2M_WIFI_RESP_PROVISION_INFO + m2m_wifi_stop_provision_mode + tstrM2MAPConfig + +@warning + DO Not use ".local" in the pcHttpServerDomainName. + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +\section Example + The example demonstrates a code snippet for how provisioning is triggered and the response event received accordingly. +@code + #include "m2m_wifi.h" + #include "m2m_types.h" + + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_PROVISION_INFO: + { + tstrM2MProvisionInfo *pstrProvInfo = (tstrM2MProvisionInfo*)pvMsg; + if(pstrProvInfo->u8Status == M2M_SUCCESS) + { + m2m_wifi_connect((char*)pstrProvInfo->au8SSID, (uint8)strlen(pstrProvInfo->au8SSID), pstrProvInfo->u8SecType, + pstrProvInfo->au8Password, M2M_WIFI_CH_ALL); + + printf("PROV SSID : %s\n",pstrProvInfo->au8SSID); + printf("PROV PSK : %s\n",pstrProvInfo->au8Password); + } + else + { + printf("(ERR) Provisioning Failed\n"); + } + } + break; + + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + tstrM2MAPConfig apConfig; + uint8 bEnableRedirect = 1; + + strcpy(apConfig.au8SSID, "WINC_SSID"); + apConfig.u8ListenChannel = 1; + apConfig.u8SecType = M2M_WIFI_SEC_OPEN; + apConfig.u8SsidHide = 0; + + // IP Address + apConfig.au8DHCPServerIP[0] = 192; + apConfig.au8DHCPServerIP[1] = 168; + apConfig.au8DHCPServerIP[2] = 1; + apConfig.au8DHCPServerIP[0] = 1; + + m2m_wifi_start_provision_mode(&apConfig, "atmelwincconf.com", bEnableRedirect); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode +*/ +NMI_API sint8 m2m_wifi_start_provision_mode(tstrM2MAPConfig *pstrAPConfig, char *pcHttpServerDomainName, uint8 bEnableHttpRedirect); + /**@}*/ +/** @defgroup StopProvisioningModeFn m2m_wifi_stop_provision_mode + * @ingroup WLANAPI + * Synchronous provision termination function which stops the provision mode if it is active. + */ + /**@{*/ +/*! +@fn \ + sint8 m2m_wifi_stop_provision_mode(void); + +@pre + An active provisioning session must be active before it is terminated through this function. +@see + m2m_wifi_start_provision_mode + +@return + The function returns ZERO for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_stop_provision_mode(void); + /**@}*/ +/** @defgroup GetConnectionInfoFn m2m_wifi_get_connection_info + * @ingroup WLANAPI + * Asynchronous connection status retrieval function, retrieves the status information of the currently connected AP. The result is passed to the Wi-Fi notification callback +* through the event @ref M2M_WIFI_RESP_CONN_INFO. Connection information is retrieved from the structure @ref tstrM2MConnInfo. + */ + /**@{*/ +/*! +@fn \ + sint8 m2m_wifi_get_connection_info(void); + +@brief + Retrieve the current Connection information. The result is passed to the Wi-Fi notification callback + with [M2M_WIFI_RESP_CONN_INFO](@ref M2M_WIFI_RESP_CONN_INFO). +@pre + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at startup. Registering the callback + is done through passing it to the initialization @ref m2m_wifi_init function. + - The event @ref M2M_WIFI_RESP_CONN_INFO must be handled in the callback to receive the requested connection info. + + Connection Information retrieved: + + + -Connection Security + -Connection RSSI + -Remote MAC address + -Remote IP address + + and in case of WINC station mode the SSID of the AP is also retrieved. +@warning + -In case of WINC AP mode or P2P mode, ignore the SSID field (NULL string). +@sa + M2M_WIFI_RESP_CONN_INFO, + tstrM2MConnInfo +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet shows an example of how wi-fi connection information is retrieved . +@code + + #include "m2m_wifi.h" + #include "m2m_types.h" + + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_CONN_INFO: + { + tstrM2MConnInfo *pstrConnInfo = (tstrM2MConnInfo*)pvMsg; + + printf("CONNECTED AP INFO\n"); + printf("SSID : %s\n",pstrConnInfo->acSSID); + printf("SEC TYPE : %d\n",pstrConnInfo->u8SecType); + printf("Signal Strength : %d\n", pstrConnInfo->s8RSSI); + printf("Local IP Address : %d.%d.%d.%d\n", + pstrConnInfo->au8IPAddr[0] , pstrConnInfo->au8IPAddr[1], pstrConnInfo->au8IPAddr[2], pstrConnInfo->au8IPAddr[3]); + } + break; + + case M2M_WIFI_REQ_DHCP_CONF: + { + // Get the current AP information. + m2m_wifi_get_connection_info(); + } + break; + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // connect to the default AP + m2m_wifi_default_connect(); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode +*/ +NMI_API sint8 m2m_wifi_get_connection_info(void); + /**@}*/ +/** @defgroup WifiSetMacAddFn m2m_wifi_set_mac_address + * @ingroup WLANAPI + * Synchronous MAC address assigning to the NMC1500. It is used for non-production SW. Assign MAC address to the WINC device. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_set_mac_address(uint8 au8MacAddress[6]); + + + +@param [in] au8MacAddress + MAC Address to be provisioned to the WINC. + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_set_mac_address(uint8 au8MacAddress[6]); + /**@}*/ +/** @defgroup WifiWpsFn m2m_wifi_wps + * @ingroup WLANAPI + * Asynchronous WPS triggering function. + * This function is called for the WINC to enter the WPS (Wi-Fi Protected Setup) mode. The result is passed to the Wi-Fi notification callback +* with the event @ref M2M_WIFI_REQ_WPS. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_wps(uint8 u8TriggerType,const char * pcPinNumber); + +@param [in] u8TriggerType + WPS Trigger method. Could be: + - [WPS_PIN_TRIGGER](@ref WPS_PIN_TRIGGER) Push button method + - [WPS_PBC_TRIGGER](@ref WPS_PBC_TRIGGER) Pin method + +@param [in] pcPinNumber + PIN number for WPS PIN method. It is not used if the trigger type is WPS_PBC_TRIGGER. It must follow the rules + stated by the WPS Standard. + +@warning + This function is not allowed in AP or P2P modes. + +@pre + - A Wi-Fi notification callback of type (@ref tpfAppWifiCb MUST be implemented and registered at startup. Registering the callback + is done through passing it to the [m2m_wifi_init](@ref m2m_wifi_init). + - The event [M2M_WIFI_REQ_WPS](@ref M2M_WIFI_REQ_WPS) must be handled in the callback to receive the WPS status. + - The WINC device MUST be in IDLE or STA mode. If AP or P2P mode is active, the WPS will not be performed. + - The [m2m_wifi_handle_events](@ref m2m_wifi_handle_events) MUST be called to receive the responses in the callback. +@see + tpfAppWifiCb + m2m_wifi_init + M2M_WIFI_REQ_WPS + tenuWPSTrigger + tstrM2MWPSInfo + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet shows an example of how wifi WPS is triggered . +@code + + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + switch(u8WiFiEvent) + { + case M2M_WIFI_REQ_WPS: + { + tstrM2MWPSInfo *pstrWPS = (tstrM2MWPSInfo*)pvMsg; + if(pstrWPS->u8AuthType != 0) + { + printf("WPS SSID : %s\n",pstrWPS->au8SSID); + printf("WPS PSK : %s\n",pstrWPS->au8PSK); + printf("WPS SSID Auth Type : %s\n",pstrWPS->u8AuthType == M2M_WIFI_SEC_OPEN ? "OPEN" : "WPA/WPA2"); + printf("WPS Channel : %d\n",pstrWPS->u8Ch + 1); + + // establish Wi-Fi connection + m2m_wifi_connect((char*)pstrWPS->au8SSID, (uint8)m2m_strlen(pstrWPS->au8SSID), + pstrWPS->u8AuthType, pstrWPS->au8PSK, pstrWPS->u8Ch); + } + else + { + printf("(ERR) WPS Is not enabled OR Timed out\n"); + } + } + break; + + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // Trigger WPS in Push button mode. + m2m_wifi_wps(WPS_PBC_TRIGGER, NULL); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode +*/ +NMI_API sint8 m2m_wifi_wps(uint8 u8TriggerType,const char *pcPinNumber); + /**@}*/ +/** @defgroup WifiWpsDisableFn m2m_wifi_wps_disable + * @ingroup WLANAPI + * Disable the NMC1500 WPS operation. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_wps_disable(void); + + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_wps_disable(void); + /**@}*/ +/** @defgroup WifiP2PFn m2m_wifi_p2p + * @ingroup WLANAPI + * Asynchronous Wi-Fi direct (P2P) enabling mode function. + The WINC supports P2P in device listening mode ONLY (intent is ZERO). + The WINC P2P implementation does not support P2P GO (Group Owner) mode. + Active P2P devices (e.g. phones) could find the WINC in the search list. When a device is connected to WINC, a Wi-Fi notification event + @ref M2M_WIFI_RESP_CON_STATE_CHANGED is triggered. After a short while, the DHCP IP Address is obtained + and an event @ref M2M_WIFI_REQ_DHCP_CONF is triggered. Refer to the code examples for a more illustrative example. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_p2p(uint8 u8Channel); + +@param [in] u8Channel + P2P Listen RF channel. According to the P2P standard It must hold only one of the following values 1, 6 or 11. + +@pre + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at initialization. Registering the callback + is done through passing it to the @ref m2m_wifi_init. + - The events @ref M2M_WIFI_RESP_CON_STATE_CHANGED and @ref M2M_WIFI_REQ_DHCP_CONF + must be handled in the callback. + - The @ref m2m_wifi_handle_events MUST be called to receive the responses in the callback. + +@warning + This function is not allowed in AP or STA modes. + +@see + tpfAppWifiCb + m2m_wifi_init + M2M_WIFI_RESP_CON_STATE_CHANGED + M2M_WIFI_REQ_DHCP_CONF + tstrM2mWifiStateChanged + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet shown an example of how the p2p mode operates. +@code + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_CON_STATE_CHANGED: + { + tstrM2mWifiStateChanged *pstrWifiState = (tstrM2mWifiStateChanged*)pvMsg; + M2M_INFO("Wifi State :: %s :: ErrCode %d\n", pstrWifiState->u8CurrState? "CONNECTED":"DISCONNECTED",pstrWifiState->u8ErrCode); + + // Do something + } + break; + + case M2M_WIFI_REQ_DHCP_CONF: + { + uint8 *pu8IPAddress = (uint8*)pvMsg; + + printf("P2P IP Address \"%u.%u.%u.%u\"\n",pu8IPAddress[0],pu8IPAddress[1],pu8IPAddress[2],pu8IPAddress[3]); + } + break; + + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // Trigger P2P + m2m_wifi_p2p(M2M_WIFI_CH_1); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode + +*/ +NMI_API sint8 m2m_wifi_p2p(uint8 u8Channel); + /**@}*/ +/** @defgroup WifiP2PDisconnectFn m2m_wifi_p2p_disconnect + * @ingroup WLANAPI + * Disable the NMC1500 device Wi-Fi direct mode (P2P). + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_p2p_disconnect(void); +@pre + The p2p mode must have be enabled and active before a disconnect can be called. +@see + m2m_wifi_p2p +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_p2p_disconnect(void); + /**@}*/ +/** @defgroup WifiEnableApFn m2m_wifi_enable_ap + * @ingroup WLANAPI + * Asynchronous wi-fi hot-spot enabling function. + * The WINC supports AP mode operation with the following limitations: + - Only 1 STA could be associated at a time. + - Open and WEP are the only supported security types + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_enable_ap(CONST tstrM2MAPConfig* pstrM2MAPConfig); + +@param [in] pstrM2MAPConfig + A structure holding the AP configurations. + +@warning + This function is not allowed in P2P or STA modes. + +@pre + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at initialization. Registering the callback + is done through passing it to the [m2m_wifi_init](@ref m2m_wifi_init). + - The event @ref M2M_WIFI_REQ_DHCP_CONF must be handled in the callback. + - The @ref m2m_wifi_handle_events MUST be called to receive the responses in the callback. + +@see + tpfAppWifiCb + tenuM2mSecType + m2m_wifi_init + M2M_WIFI_REQ_DHCP_CONF + tstrM2mWifiStateChanged + tstrM2MAPConfig + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet demonstrates how the AP mode is enabled after the driver is initialized in the application's main function and the handling + of the event @ref M2M_WIFI_REQ_DHCP_CONF, to indicate successful connection. +@code + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + switch(u8WiFiEvent) + { + case M2M_WIFI_REQ_DHCP_CONF: + { + uint8 *pu8IPAddress = (uint8*)pvMsg; + + printf("Associated STA has IP Address \"%u.%u.%u.%u\"\n",pu8IPAddress[0],pu8IPAddress[1],pu8IPAddress[2],pu8IPAddress[3]); + } + break; + + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + tstrM2MAPConfig apConfig; + + strcpy(apConfig.au8SSID, "WINC_SSID"); + apConfig.u8ListenChannel = 1; + apConfig.u8SecType = M2M_WIFI_SEC_OPEN; + apConfig.u8SsidHide = 0; + + // IP Address + apConfig.au8DHCPServerIP[0] = 192; + apConfig.au8DHCPServerIP[1] = 168; + apConfig.au8DHCPServerIP[2] = 1; + apConfig.au8DHCPServerIP[0] = 1; + + // Trigger AP + m2m_wifi_enable_ap(&apConfig); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode + +*/ +NMI_API sint8 m2m_wifi_enable_ap(CONST tstrM2MAPConfig* pstrM2MAPConfig); + /**@}*/ +/** @defgroup WifiDisableApFn m2m_wifi_disable_ap + * @ingroup WLANAPI + * Synchronous wi-fi hot-spot disabling function. Must be called only when the AP is enabled through the @ref m2m_wifi_enable_ap + * function. Otherwise the call to this function will not be useful. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_disable_ap(void); +@see + m2m_wifi_enable_ap +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_disable_ap(void); + /**@}*/ +/** @defgroup SetStaticIPFn m2m_wifi_set_static_ip + * @ingroup WLANAPI + * Synchronous static IP Address configuration function. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_set_static_ip(tstrM2MIPConfig * pstrStaticIPConf); + +@param [in] pstrStaticIPConf + Pointer to a structure holding the static IP Configurations (IP, + Gateway, subnet mask and DNS address). + +@warning + This function should not be used. DHCP configuration is requested automatically after successful Wi-Fi connection is established. + +@see + tstrM2MIPConfig + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_set_static_ip(tstrM2MIPConfig * pstrStaticIPConf); + /**@}*/ +/** @defgroup RequestDHCPClientFn m2m_wifi_request_dhcp_client + * @ingroup WLANAPI + * Starts the DHCP client operation(DHCP requested by the firmware automatically in STA/AP/P2P mode). + * + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_request_dhcp_client(void); + +@warning + This function should not be used. DHCP configuration is requested automatically after successful Wi-Fi connection is established. + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_request_dhcp_client(void); + /**@}*/ +/** @defgroup RequestDHCPServerFn m2m_wifi_request_dhcp_server + * @ingroup WLANAPI + * Dhcp requested by the firmware automatically in STA/AP/P2P mode). + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_request_dhcp_server(uint8* addr); + +@warning + This function is not used in the current releases. DHCP server is started automatically when enabling the AP mode. + + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_request_dhcp_server(uint8* addr); + /**@}*/ +/** @defgroup WifiSetScanOptionFn m2m_wifi_set_scan_options + * @ingroup WLANAPI + * Synchronous wi-fi scan settings function. This function sets the time configuration parameters for the scan operation. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_enable_dhcp(uint8 u8DhcpEn ); + +@brief + Enable/Disable the DHCP client after connection. + +@param [in] u8DhcpEn + Possible values: + 1: Enable DHCP client after connection. + 0: Disable DHCP client after connection. +@warnings + - DHCP client is enabled by default + -This Function should be called before using m2m_wifi_set_static_ip() + + +@sa + m2m_wifi_set_static_ip() + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_enable_dhcp(uint8 u8DhcpEn ); + + +/*! +@fn \ + sint8 m2m_wifi_set_scan_options(tstrM2MScanOption* ptstrM2MScanOption) + +@param [in] ptstrM2MScanOption; + Pointer to the structure holding the Scan Parameters. + +@see + tenuM2mScanCh + m2m_wifi_request_scan + tstrM2MScanOption + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_set_scan_options(tstrM2MScanOption* ptstrM2MScanOption); + /**@}*/ +/** @defgroup WifiSetScanRegionFn m2m_wifi_set_scan_region + * @ingroup WLANAPI + * Synchronous wi-fi scan region setting function. + * This function sets the scan region, which will affect the range of possible scan channels. + * For 2.5GHz supported in the current release, the requested scan region can't exceed the maximum number of channels (14). + *@{*/ +/*! +@fn \ + sint8 m2m_wifi_set_scan_region(uint16 ScanRegion) + +@param [in] ScanRegion; + ASIA + NORTH_AMERICA +@see + tenuM2mScanCh + m2m_wifi_request_scan + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_set_scan_region(uint16 ScanRegion); + /**@}*/ +/** @defgroup WifiRequestScanFn m2m_wifi_request_scan +* @ingroup WLANAPI +* Asynchronous wi-fi scan request on the given channel. The scan status is delivered in the wi-fi event callback and then the application +* is to read the scan results sequentially. +* The number of APs found (N) is returned in event @ref M2M_WIFI_RESP_SCAN_DONE with the number of found +* APs. +* The application could read the list of APs by calling the function @ref m2m_wifi_req_scan_result N times. +* +*@{*/ +/*! +@fn \ + NMI_API sint8 m2m_wifi_request_scan(uint8 ch); + +@param [in] ch + RF Channel ID for SCAN operation. It should be set according to tenuM2mScanCh. + With a value of M2M_WIFI_CH_ALL(255)), means to scan all channels. + +@warning + This function is not allowed in P2P or AP modes. It works only for STA mode (connected or disconnected). + +@pre + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at initialization. Registering the callback + is done through passing it to the @ref m2m_wifi_init. + - The events @ref M2M_WIFI_RESP_SCAN_DONE and @ref M2M_WIFI_RESP_SCAN_RESULT. + must be handled in the callback. + - The @ref m2m_wifi_handle_events function MUST be called to receive the responses in the callback. + +@see + M2M_WIFI_RESP_SCAN_DONE + M2M_WIFI_RESP_SCAN_RESULT + tpfAppWifiCb + tstrM2mWifiscanResult + tenuM2mScanCh + m2m_wifi_init + m2m_wifi_handle_events + m2m_wifi_req_scan_result + +@return + The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet demonstrates an example of how the scan request is called from the application's main function and the handling of + the events received in response. +@code + + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + static uint8 u8ScanResultIdx = 0; + + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_SCAN_DONE: + { + tstrM2mScanDone *pstrInfo = (tstrM2mScanDone*)pvMsg; + + printf("Num of AP found %d\n",pstrInfo->u8NumofCh); + if(pstrInfo->s8ScanState == M2M_SUCCESS) + { + u8ScanResultIdx = 0; + if(pstrInfo->u8NumofCh >= 1) + { + m2m_wifi_req_scan_result(u8ScanResultIdx); + u8ScanResultIdx ++; + } + else + { + printf("No AP Found Rescan\n"); + m2m_wifi_request_scan(M2M_WIFI_CH_ALL); + } + } + else + { + printf("(ERR) Scan fail with error <%d>\n",pstrInfo->s8ScanState); + } + } + break; + + case M2M_WIFI_RESP_SCAN_RESULT: + { + tstrM2mWifiscanResult *pstrScanResult =(tstrM2mWifiscanResult*)pvMsg; + uint8 u8NumFoundAPs = m2m_wifi_get_num_ap_found(); + + printf(">>%02d RI %d SEC %s CH %02d BSSID %02X:%02X:%02X:%02X:%02X:%02X SSID %s\n", + pstrScanResult->u8index,pstrScanResult->s8rssi, + pstrScanResult->u8AuthType, + pstrScanResult->u8ch, + pstrScanResult->au8BSSID[0], pstrScanResult->au8BSSID[1], pstrScanResult->au8BSSID[2], + pstrScanResult->au8BSSID[3], pstrScanResult->au8BSSID[4], pstrScanResult->au8BSSID[5], + pstrScanResult->au8SSID); + + if(u8ScanResultIdx < u8NumFoundAPs) + { + // Read the next scan result + m2m_wifi_req_scan_result(index); + u8ScanResultIdx ++; + } + } + break; + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // Scan all channels + m2m_wifi_request_scan(M2M_WIFI_CH_ALL); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode +*/ +NMI_API sint8 m2m_wifi_request_scan(uint8 ch); +/**@}*/ +/** @defgroup WifiGetNumAPFoundFn m2m_wifi_get_num_ap_found + * @ingroup WLANAPI +* Synchronous function to retrieve the number of AP's found in the last scan request, The function read the number of AP's from global variable which updated in the Wi-Fi callback function through the M2M_WIFI_RESP_SCAN_DONE event. +* Function used only in STA mode only. + */ + /**@{*/ +/*! +@fn NMI_API uint8 m2m_wifi_get_num_ap_found(void); + +@see m2m_wifi_request_scan + M2M_WIFI_RESP_SCAN_DONE + M2M_WIFI_RESP_SCAN_RESULT +@pre m2m_wifi_request_scan need to be called first + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at initialization. Registering the callback + is done through passing it to the @ref m2m_wifi_init. + - The event @ref M2M_WIFI_RESP_SCAN_DONE must be handled in the callback to receive the requested connection information. +@warning This function must be called only in the wi-fi callback function when the events @ref M2M_WIFI_RESP_SCAN_DONE or @ref M2M_WIFI_RESP_SCAN_RESULT + are received. + Calling this function in any other place will result in undefined/outdated numbers. +@return Return the number of AP's found in the last Scan Request. + +\section Example + The code snippet demonstrates an example of how the scan request is called from the application's main function and the handling of + the events received in response. +@code + + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + static uint8 u8ScanResultIdx = 0; + + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_SCAN_DONE: + { + tstrM2mScanDone *pstrInfo = (tstrM2mScanDone*)pvMsg; + + printf("Num of AP found %d\n",pstrInfo->u8NumofCh); + if(pstrInfo->s8ScanState == M2M_SUCCESS) + { + u8ScanResultIdx = 0; + if(pstrInfo->u8NumofCh >= 1) + { + m2m_wifi_req_scan_result(u8ScanResultIdx); + u8ScanResultIdx ++; + } + else + { + printf("No AP Found Rescan\n"); + m2m_wifi_request_scan(M2M_WIFI_CH_ALL); + } + } + else + { + printf("(ERR) Scan fail with error <%d>\n",pstrInfo->s8ScanState); + } + } + break; + + case M2M_WIFI_RESP_SCAN_RESULT: + { + tstrM2mWifiscanResult *pstrScanResult =(tstrM2mWifiscanResult*)pvMsg; + uint8 u8NumFoundAPs = m2m_wifi_get_num_ap_found(); + + printf(">>%02d RI %d SEC %s CH %02d BSSID %02X:%02X:%02X:%02X:%02X:%02X SSID %s\n", + pstrScanResult->u8index,pstrScanResult->s8rssi, + pstrScanResult->u8AuthType, + pstrScanResult->u8ch, + pstrScanResult->au8BSSID[0], pstrScanResult->au8BSSID[1], pstrScanResult->au8BSSID[2], + pstrScanResult->au8BSSID[3], pstrScanResult->au8BSSID[4], pstrScanResult->au8BSSID[5], + pstrScanResult->au8SSID); + + if(u8ScanResultIdx < u8NumFoundAPs) + { + // Read the next scan result + m2m_wifi_req_scan_result(index); + u8ScanResultIdx ++; + } + } + break; + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // Scan all channels + m2m_wifi_request_scan(M2M_WIFI_CH_ALL); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode +*/ +NMI_API uint8 m2m_wifi_get_num_ap_found(void); +/**@}*/ +/** @defgroup WifiReqScanResult m2m_wifi_req_scan_result +* @ingroup WLANAPI +* Synchronous call to read the AP information from the SCAN Result list with the given index. +* This function is expected to be called when the response events M2M_WIFI_RESP_SCAN_RESULT or +* M2M_WIFI_RESP_SCAN_DONE are received in the wi-fi callback function. +* The response information received can be obtained through the casting to the @ref tstrM2mWifiscanResult structure + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_req_scan_result(uint8 index); +@param [in] index + Index for the requested result, the index range start from 0 till number of AP's found + +@see tstrM2mWifiscanResult + m2m_wifi_get_num_ap_found + m2m_wifi_request_scan + +@pre @ref m2m_wifi_request_scan needs to be called first, then m2m_wifi_get_num_ap_found + to get the number of AP's found + - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered at startup. Registering the callback + is done through passing it to the @ref m2m_wifi_init function. + - The event @ref M2M_WIFI_RESP_SCAN_RESULT must be handled in the callback to receive the requested connection information. +@warning Function used in STA mode only. the scan results are updated only if the scan request is called. + Calling this function only without a scan request will lead to firmware errors. + Refrain from introducing a large delay between the scan request and the scan result request, to prevent + an errors occurring. + +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet demonstrates an example of how the scan request is called from the application's main function and the handling of + the events received in response. +@code + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + static uint8 u8ScanResultIdx = 0; + + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_SCAN_DONE: + { + tstrM2mScanDone *pstrInfo = (tstrM2mScanDone*)pvMsg; + + printf("Num of AP found %d\n",pstrInfo->u8NumofCh); + if(pstrInfo->s8ScanState == M2M_SUCCESS) + { + u8ScanResultIdx = 0; + if(pstrInfo->u8NumofCh >= 1) + { + m2m_wifi_req_scan_result(u8ScanResultIdx); + u8ScanResultIdx ++; + } + else + { + printf("No AP Found Rescan\n"); + m2m_wifi_request_scan(M2M_WIFI_CH_ALL); + } + } + else + { + printf("(ERR) Scan fail with error <%d>\n",pstrInfo->s8ScanState); + } + } + break; + + case M2M_WIFI_RESP_SCAN_RESULT: + { + tstrM2mWifiscanResult *pstrScanResult =(tstrM2mWifiscanResult*)pvMsg; + uint8 u8NumFoundAPs = m2m_wifi_get_num_ap_found(); + + printf(">>%02d RI %d SEC %s CH %02d BSSID %02X:%02X:%02X:%02X:%02X:%02X SSID %s\n", + pstrScanResult->u8index,pstrScanResult->s8rssi, + pstrScanResult->u8AuthType, + pstrScanResult->u8ch, + pstrScanResult->au8BSSID[0], pstrScanResult->au8BSSID[1], pstrScanResult->au8BSSID[2], + pstrScanResult->au8BSSID[3], pstrScanResult->au8BSSID[4], pstrScanResult->au8BSSID[5], + pstrScanResult->au8SSID); + + if(u8ScanResultIdx < u8NumFoundAPs) + { + // Read the next scan result + m2m_wifi_req_scan_result(index); + u8ScanResultIdx ++; + } + } + break; + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // Scan all channels + m2m_wifi_request_scan(M2M_WIFI_CH_ALL); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode +*/ +NMI_API sint8 m2m_wifi_req_scan_result(uint8 index); +/**@}*/ +/** @defgroup WifiReqCurrentRssiFn m2m_wifi_req_curr_rssi + * @ingroup WLANAPI + * Asynchronous request for the current RSSI of the connected AP. + * The response received in through the @ref M2M_WIFI_RESP_CURRENT_RSSI event. + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_req_curr_rssi(void); +@pre - A Wi-Fi notification callback of type @ref tpfAppWifiCb MUST be implemented and registered before initialization. Registering the callback + is done through passing it to the [m2m_wifi_init](@ref m2m_wifi_init) through the @ref tstrWifiInitParam initialization structure. + - The event @ref M2M_WIFI_RESP_CURRENT_RSSI must be handled in the callback to receive the requested connection information. +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +\section Example + The code snippet demonstrates how the RSSI request is called in the application's main function and the handling of event received in the callback. +@code + + #include "m2m_wifi.h" + #include "m2m_types.h" + + void wifi_event_cb(uint8 u8WiFiEvent, void * pvMsg) + { + static uint8 u8ScanResultIdx = 0; + + switch(u8WiFiEvent) + { + case M2M_WIFI_RESP_CURRENT_RSSI: + { + sint8 *rssi = (sint8*)pvMsg; + M2M_INFO("ch rssi %d\n",*rssi); + } + break; + default: + break; + } + } + + int main() + { + tstrWifiInitParam param; + + param.pfAppWifiCb = wifi_event_cb; + if(!m2m_wifi_init(¶m)) + { + // Scan all channels + m2m_wifi_req_curr_rssi(); + + while(1) + { + m2m_wifi_handle_events(NULL); + } + } + } + +@endcode + +*/ +NMI_API sint8 m2m_wifi_req_curr_rssi(void); +/**@}*/ +/** @defgroup WifiGetOtpMacAddFn m2m_wifi_get_otp_mac_address +* @ingroup WLANAPI +* Request the MAC address stored on the OTP (one time programmable) memory of the device. +* The function is blocking until the response is received. +*/ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_get_otp_mac_address(uint8 *pu8MacAddr, uint8 * pu8IsValid); + +@param [out] pu8MacAddr + Output MAC address buffer of 6 bytes size. Valid only if *pu8Valid=1. +@param [out] pu8IsValid + A output boolean value to indicate the validity of pu8MacAddr in OTP. + Output zero if the OTP memory is not programmed, non-zero otherwise. +@pre m2m_wifi_init required to call any WIFI/socket function +@see m2m_wifi_get_mac_address + +@return The function returns @ref M2M_SUCCESS for success and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_get_otp_mac_address(uint8 *pu8MacAddr, uint8 * pu8IsValid); +/**@}*/ +/** @defgroup WifiGetMacAddFn m2m_wifi_get_mac_address +* @ingroup WLANAPI +* Function to retrieve the current MAC address. The function is blocking until the response is received. +*/ +/**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_get_mac_address(uint8 *pu8MacAddr) +@param [out] pu8MacAddr + Output MAC address buffer of 6 bytes size. +@pre m2m_wifi_init required to call any WIFI/socket function +@see m2m_wifi_get_otp_mac_address +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_get_mac_address(uint8 *pu8MacAddr); +/**@}*/ +/** @defgroup SetSleepModeFn m2m_wifi_set_sleep_mode + * @ingroup WLANAPI + * Synchronous power-save mode setting function for the NMC1500. + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_set_sleep_mode(uint8 PsTyp, uint8 BcastEn); +@param [in] PsTyp + Desired power saving mode. Supported types are defined in @ref tenuPowerSaveModes. +@param [in] BcastEn + Broadcast reception enable flag. + If it is 1, the WINC1500 must be awake each DTIM beacon for receiving broadcast traffic. + If it is 0, the WINC1500 will not wakeup at the DTIM beacon, but its wakeup depends only + on the the configured Listen Interval. + +@warning The function called once after initialization. + +@see tenuPowerSaveModes + m2m_wifi_get_sleep_mode + +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_set_sleep_mode(uint8 PsTyp, uint8 BcastEn); +/**@}*/ +/** @defgroup WifiRequestSleepFn m2m_wifi_request_sleep + * @ingroup WLANAPI + * Synchronous power save request function, which requests from the NMC1500 device to sleep in the mode previously set + * for a specific time. + * This function should be used in the M2M_PS_MANUAL Power save mode (only). + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_request_sleep(uint32 u32SlpReqTime); +@param [in] u32SlpReqTime + Request Sleep in ms +@warning The function should be called in M2M_PS_MANUAL power save only. +@see tenuPowerSaveModes + m2m_wifi_set_sleep_mode +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_request_sleep(uint32 u32SlpReqTime); +/**@}*/ +/** @defgroup GetSleepModeFn m2m_wifi_get_sleep_mode + * @ingroup WLANAPI + * Synchronous power save mode retrieval function. + */ + /**@{*/ +/*! +@fn NMI_API uint8 m2m_wifi_get_sleep_mode(void); +@see tenuPowerSaveModes + m2m_wifi_set_sleep_mode +@return The current operating power saving mode. + +*/ +NMI_API uint8 m2m_wifi_get_sleep_mode(void); +/**@}*/ +/** @defgroup WifiReqClientCtrlFn m2m_wifi_req_client_ctrl + * @ingroup WLANAPI + * Asynchronous command sending function to the PS Client (An NMC1500 board running the ps_firmware) +* if the PS client send any commands it will be received through the @ref M2M_WIFI_RESP_CLIENT_INFO event + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_req_client_ctrl(uint8 cmd); +@brief +@param [in] cmd + Control command sent from PS Server to PS Client (command values defined by the application) +@pre m2m_wifi_req_server_init should be called first +@warning This mode is not supported in the current release. +@see m2m_wifi_req_server_init + M2M_WIFI_RESP_CLIENT_INFO +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_req_client_ctrl(uint8 cmd); +/**@}*/ +/** @defgroup WifiReqServerInit m2m_wifi_req_server_init + * @ingroup WLANAPI + * Synchronous function to initialize the PS Server. + * The WINC1500 supports non secure communication with another WINC1500, +* (SERVER/CLIENT) through one byte command (probe request and probe response) without any connection setup. +* The server mode can't be used with any other modes (STA/P2P/AP) +*/ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_req_server_init(uint8 ch); +@param [in] ch + Server listening channel +@see m2m_wifi_req_client_ctrl +@warning This mode is not supported in the current release. +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_req_server_init(uint8 ch); +/**@}*/ +/** @defgroup WifiSetDeviceNameFn m2m_wifi_set_device_name + * @ingroup WLANAPI + * Set the WINC1500 device name which is to be used as a P2P device name. + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_set_device_name(uint8 *pu8DeviceName, uint8 u8DeviceNameLength); +@param [in] pu8DeviceName + Buffer holding the device name. +@param [in] u8DeviceNameLength + Length of the device name. Should not exceed the maximum device name's length M2M_DEVICE_NAME_MAX. +@warning The function called once after initialization. +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_set_device_name(uint8 *pu8DeviceName, uint8 u8DeviceNameLength); +/**@}*/ +/** @defgroup WifiSetLsnIntFn m2m_wifi_set_lsn_int + * @ingroup WLANAPI +* Synchronous function for setting the wi-fi listen interval for power save operation. It is represented in units +* of AP Beacon periods. + */ + /**@{*/ +/*! +@fn NMI_API sint8 m2m_wifi_set_lsn_int(tstrM2mLsnInt * pstrM2mLsnInt); + +@param [in] pstrM2mLsnInt + Structure holding the listen interval configurations. +@pre Function m2m_wifi_set_sleep_mode shall be called first +@warning The function should be called once after initialization. +@see tstrM2mLsnInt + m2m_wifi_set_sleep_mode +@return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*/ +NMI_API sint8 m2m_wifi_set_lsn_int(tstrM2mLsnInt *pstrM2mLsnInt); +/**@}*/ +/** @defgroup WifiEnableMonitorModeFn m2m_wifi_enable_monitoring_mode + * @ingroup WLANAPI + * Asynchronous wi-fi monitoring enable mode (Promiscuous mode) function. This function enables the monitoring mode, which starts transmission + * of the packets based on the filter information passed in as a parameter. All packets that meet the filtering criteria are passed to the application layer, to be handled by the assigned monitoring callback function. + * The monitoring callback function must be implemented before starting the monitoring mode, in-order to handle the packets received. + * Registering of the implemented callback function is through the callback pointer @ref tpfAppMonCb in the @ref tstrWifiInitParam structure. + * passed to @ref m2m_wifi_init function at initialization. + * + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_enable_monitoring_mode(tstrM2MWifiMonitorModeCtrl *, uint8 *, uint16 , uint16); + * @param [in] pstrMtrCtrl + * Pointer to @ref tstrM2MWifiMonitorModeCtrl structure holding the Filtering parameters. + * @param [in] pu8PayloadBuffer + * Pointer to a Buffer allocated by the application. The buffer SHALL hold the Data field of + * the WIFI RX Packet (Or a part from it). If it is set to NULL, the WIFI data payload will + * be discarded by the monitoring driver. + * @param [in] u16BufferSize + * The total size of the pu8PayloadBuffer in bytes. + * @param [in] u16DataOffset + * Starting offset in the DATA FIELD of the received WIFI packet. The application may be interested + * in reading specific information from the received packet. It must assign the offset to the starting + * position of it relative to the DATA payload start.\n + * \e Example, \e if \e the \e SSID \e is \e needed \e to \e be \e read \e from \e a \e PROBE \e REQ \e packet, \e the \e u16Offset \e MUST \e be \e set \e to \e 0. + * @warning This mode available as sniffer ONLY, you can not be connected in any modes (Station, Access Point, or P2P).\n + * @see tstrM2MWifiMonitorModeCtrl + tstrM2MWifiRxPacketInfo + tstrWifiInitParam + tenuM2mScanCh + m2m_wifi_disable_monitoring_mode + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + +*\section Example +* The example demonstrates the main function where-by the monitoring enable function is called after the initialization of the driver and the packets are +* handled in the callback function. +* @code + + #include "m2m_wifi.h" + #include "m2m_types.h" + + //Declare receive buffer + uint8 gmgmt[1600]; + + //Callback functions + void wifi_cb(uint8 u8WiFiEvent, void * pvMsg) + { + ; + } + void wifi_monitoring_cb(tstrM2MWifiRxPacketInfo *pstrWifiRxPacket, uint8 *pu8Payload, uint16 u16PayloadSize) + { + if((NULL != pstrWifiRxPacket) && (0 != u16PayloadSize)) { + if(MANAGEMENT == pstrWifiRxPacket->u8FrameType) { + M2M_INFO("***# MGMT PACKET #***\n"); + } else if(DATA_BASICTYPE == pstrWifiRxPacket->u8FrameType) { + M2M_INFO("***# DATA PACKET #***\n"); + } else if(CONTROL == pstrWifiRxPacket->u8FrameType) { + M2M_INFO("***# CONTROL PACKET #***\n"); + } + } + } + + int main() + { + //Register wifi_monitoring_cb + tstrWifiInitParam param; + param.pfAppWifiCb = wifi_cb; + param.pfAppMonCb = wifi_monitoring_cb; + + nm_bsp_init(); + + if(!m2m_wifi_init(¶m)) { + //Enable Monitor Mode with filter to receive all data frames on channel 1 + tstrM2MWifiMonitorModeCtrl strMonitorCtrl = {0}; + strMonitorCtrl.u8ChannelID = M2M_WIFI_CH_1; + strMonitorCtrl.u8FrameType = DATA_BASICTYPE; + strMonitorCtrl.u8FrameSubtype = M2M_WIFI_FRAME_SUB_TYPE_ANY; //Receive any subtype of data frame + m2m_wifi_enable_monitoring_mode(&strMonitorCtrl, gmgmt, sizeof(gmgmt), 0); + + while(1) { + m2m_wifi_handle_events(NULL); + } + } + return 0; + } + * @endcode + */ +NMI_API sint8 m2m_wifi_enable_monitoring_mode(tstrM2MWifiMonitorModeCtrl *pstrMtrCtrl, uint8 *pu8PayloadBuffer, + uint16 u16BufferSize, uint16 u16DataOffset); +/**@}*/ +/** @defgroup WifiDisableMonitorModeFn m2m_wifi_disable_monitoring_mode + * @ingroup WLANAPI + * Synchronous function to disable Wi-Fi monitoring mode (Promiscuous mode). Expected to be called, if the enable monitoring mode is set, but if it was called without enabling + * no negative impact will reside. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_disable_monitoring_mode(void); + * @see m2m_wifi_enable_monitoring_mode + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_disable_monitoring_mode(void); + /**@}*/ + /** @defgroup SendWlanPktFn m2m_wifi_send_wlan_pkt + * @ingroup WLANAPI + * Synchronous function to transmit a WIFI RAW packet while the implementation of this packet is left to the application developer. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_send_wlan_pkt(uint8 *, uint16, uint16); + + * @param [in] pu8WlanPacket + * Pointer to a buffer holding the whole WIFI frame. + * @param [in] u16WlanHeaderLength + * The size of the WIFI packet header ONLY. + * @param [in] u16WlanPktSize + * The size of the whole bytes in packet. + * @see m2m_wifi_enable_monitoring_mode + m2m_wifi_disable_monitoring_mode + * @pre Enable Monitoring mode first using @ref m2m_wifi_enable_monitoring_mode + * @warning This function available in monitoring mode ONLY.\n + * @note Packets are user's responsibility. + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_send_wlan_pkt(uint8 *pu8WlanPacket, uint16 u16WlanHeaderLength, uint16 u16WlanPktSize); +/**@}*/ +/** @defgroup WifiSendEthernetPktFn m2m_wifi_send_ethernet_pkt + * @ingroup WLANAPI + * Synchronous function to transmit an Ethernet packet. Transmit a packet directly in bypass mode where the TCP/IP stack is disabled and the implementation of this packet is left to the application developer. + * The Ethernet packet composition is left to the application developer. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_send_ethernet_pkt(uint8* pu8Packet,uint16 u16PacketSize) + * @param [in] pu8Packet + * Pointer to a buffer holding the whole Ethernet frame. + * @param [in] u16PacketSize + * The size of the whole bytes in packet. + * @attention This function available in Bypass mode ONLY. Make sure that firmware version built with macro \ref ETH_MODE.\n + * @note Packets are the user's responsibility. + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + + */ +NMI_API sint8 m2m_wifi_send_ethernet_pkt(uint8* pu8Packet,uint16 u16PacketSize); +/**@}*/ +/** @defgroup WifiEnableSntpFn m2m_wifi_enable_sntp + * @ingroup WLANAPI + * Synchronous function to Enable/Disable the native SNTP client in the m2m firmware. The SNTP is enabled by default at start-up. + * The SNTP client at firmware is used to sync the system clock to the UTC time from well known time + * servers (e.g. "time-c.nist.gov"). The SNTP client uses a default update cycle of 1 day. + * The UTC is important for checking the expiration date of X509 certificates used while establishing + * TLS (Transport Layer Security) connections. + * It is highly recommended to use it if there is no other means to get the UTC time. If there is a RTC + * on the host MCU, the SNTP could be disabled and the host should set the system time to the firmware + * using the @ref m2m_wifi_set_system_time function. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_enable_sntp(uint8); + * @param [in] bEnable +* Enabling/Disabling flag + * '0' :disable SNTP + * '1' :enable SNTP + * @see m2m_wifi_set_sytem_time + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_enable_sntp(uint8 bEnable); +/**@}*/ +/** @defgroup WifiSetSystemTime m2m_wifi_set_sytem_time + * @ingroup WLANAPI + * Synchronous function for setting the system time in time/date format (@ref uint32).\n + * The @ref tstrSystemTime structure can be used as a reference to the time values that should be set and pass its value as @ref uint32 + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_set_sytem_time(uint32); + * @param [in] u32UTCSeconds + * Seconds elapsed since January 1, 1900 (NTP Timestamp). + * @see m2m_wifi_enable_sntp + tstrSystemTime + * @note If there is an RTC on the host MCU, the SNTP could be disabled and the host should set the system time to the firmware + * using the API \ref m2m_wifi_set_sytem_time. + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_set_sytem_time(uint32 u32UTCSeconds); +/*! + * @fn NMI_API sint8 m2m_wifi_get_sytem_time(void); + * @see m2m_wifi_enable_sntp + tstrSystemTime + * @note get the system time from the sntp client + * using the API \ref m2m_wifi_get_sytem_time. + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_get_sytem_time(void); +/**@}*/ +/** @defgroup WifiSetCustInfoElementFn m2m_wifi_set_cust_InfoElement + * @ingroup WLANAPI + * Synchronous function to Add/Remove user-defined Information Element to the WIFIBeacon and Probe Response frames while chip mode is Access Point Mode.\n + * According to the information element layout shown bellow, if it is required to set new data for the information elements, pass in the buffer with the + * information according to the sizes and ordering defined bellow. However, if it's required to delete these IEs, fill the buffer with zeros. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_set_cust_InfoElement(uint8*); + * @param [in] pau8M2mCustInfoElement + * Pointer to Buffer containing the IE to be sent. It is the application developer's responsibility to ensure on the correctness of the information element's ordering passed in. + * @warning - Size of All elements combined must not exceed 255 byte.\n + * - Used in Access Point Mode \n + * @note IEs Format will be follow the following layout:\n + * @verbatim + --------------- ---------- ---------- ------------------- -------- -------- ----------- ---------------------- + | Byte[0] | Byte[1] | Byte[2] | Byte[3:length1+2] | ..... | Byte[n] | Byte[n+1] | Byte[n+2:lengthx+2] | + |---------------|----------|----------|-------------------|-------- --------|-----------|------------------| + | #of all Bytes | IE1 ID | Length1 | Data1(Hex Coded) | ..... | IEx ID | Lengthx | Datax(Hex Coded) | + --------------- ---------- ---------- ------------------- -------- -------- ----------- ---------------------- + * @endverbatim + * @see m2m_wifi_enable_sntp + * tstrSystemTime + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + \section Example + The example demonstrates how the information elements are set using this function. + *@code + * + char elementData[21]; + static char state = 0; // To Add, Append, and Delete + if(0 == state) { //Add 3 IEs + state = 1; + //Total Number of Bytes + elementData[0]=12; + //First IE + elementData[1]=200; elementData[2]=1; elementData[3]='A'; + //Second IE + elementData[4]=201; elementData[5]=2; elementData[6]='B'; elementData[7]='C'; + //Third IE + elementData[8]=202; elementData[9]=3; elementData[10]='D'; elementData[11]=0; elementData[12]='F'; + } else if(1 == state) { + //Append 2 IEs to others, Notice that we keep old data in array starting with\n + //element 13 and total number of bytes increased to 20 + state = 2; + //Total Number of Bytes + elementData[0]=20; + //Fourth IE + elementData[13]=203; elementData[14]=1; elementData[15]='G'; + //Fifth IE + elementData[16]=204; elementData[17]=3; elementData[18]='X'; elementData[19]=5; elementData[20]='Z'; + } else if(2 == state) { //Delete All IEs + state = 0; + //Total Number of Bytes + elementData[0]=0; + } + m2m_wifi_set_cust_InfoElement(elementData); + * @endcode + */ +NMI_API sint8 m2m_wifi_set_cust_InfoElement(uint8* pau8M2mCustInfoElement); + +/*! +@fn NMI_API sint8 m2m_wifi_set_power_profile(uint8 u8PwrMode); +@brief Change the power profile mode +@param [in] u8PwrMode + Change the WINC power profile to different mode + PWR_LOW1/PWR_LOW2/PWR_HIGH/PWR_AUTO (tenuM2mPwrMode) +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa tenuM2mPwrMode +@pre m2m_wifi_init +@warning must be called after the initializations and before any connection request and can't be changed in run time, +*/ +sint8 m2m_wifi_set_power_profile(uint8 u8PwrMode); +/*! +@fn NMI_API sint8 m2m_wifi_set_tx_power(uint8 u8TxPwrLevel); +@brief set the TX power tenuM2mTxPwrLevel +@param [in] u8TxPwrLevel + change the TX power tenuM2mTxPwrLevel +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa tenuM2mTxPwrLevel +@pre m2m_wifi_init +@warning +*/ +sint8 m2m_wifi_set_tx_power(uint8 u8TxPwrLevel); + +/*! +@fn NMI_API sint8 m2m_wifi_enable_firmware_logs(uint8 u8Enable); +@brief Enable or Disable logs in run time (Disable Firmware logs will + enhance the firmware start-up time and performance) +@param [in] u8Enable + Set 1 to enable the logs 0 for disable +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa __DISABLE_FIRMWARE_LOGS__ (build option to disable logs from initializations) +@pre m2m_wifi_init +@warning +*/ +sint8 m2m_wifi_enable_firmware_logs(uint8 u8Enable); +/*! +@fn NMI_API sint8 m2m_wifi_set_battery_voltage(uint8 u8BattVolt) +@brief Set the battery voltage to update the firmware calculations +@param [in] dbBattVolt + Battery Volt in double +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa +@pre m2m_wifi_init +@warning +*/ +sint8 m2m_wifi_set_battery_voltage(uint16 u16BattVoltx100); +/** +* @fn m2m_wifi_get_firmware_version(tstrM2mRev* pstrRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters +* @version 1.0 +*/ +sint8 m2m_wifi_get_firmware_version(tstrM2mRev *pstrRev); +/**@}*/ +#ifdef ETH_MODE +/** @defgroup WifiEnableMacMcastFn m2m_wifi_enable_mac_mcast + * @ingroup WLANAPI + * Synchronous function to Add/Remove MAC addresses in the multicast filter to receive multicast packets in bypass mode. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_enable_mac_mcast(uint8 *, uint8); + * @brief + * @param [in] pu8MulticastMacAddress + * Pointer to MAC address + * @param [in] u8AddRemove + * A flag to add or remove the MAC ADDRESS, based on the following values: + * - 0 : remove MAC address + * - 1 : add MAC address + * @attention This function is available in bypass mode ONLY. Make sure that firmware version built with the macro @ref ETH_MODE.\n + * @note Maximum number of MAC addresses that could be added is 8. + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_enable_mac_mcast(uint8* pu8MulticastMacAddress, uint8 u8AddRemove); +/**@}*/ +/** @defgroup SetReceiveBufferFn m2m_wifi_set_receive_buffer + * @ingroup WLANAPI + * Synchronous function for setting or changing the receiver buffer's length. + * Changes are made according to the developer option in bypass mode and this function should be called in the receive callback handling. + *@{*/ +/*! + * @fn NMI_API sint8 m2m_wifi_set_receive_buffer(void *, uint16); + + * @param [in] pvBuffer + * Pointer to Buffer to receive data. + * NULL pointer causes a negative error @ref M2M_ERR_FAIL. + * + * @param [in] u16BufferLen + * Length of data to be received. Maximum length of data should not exceed the size defined by TCP/IP + * defined as @ref SOCKET_BUFFER_MAX_LENGTH + * + * @warning This function is available in the bypass mode ONLY. Make sure that firmware version is built with macro @ref ETH_MODE.\n + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_wifi_set_receive_buffer(void* pvBuffer,uint16 u16BufferLen); +/**@}*/ +#endif /* ETH_MODE */ +/*! + * @fn sint8 m2m_wifi_prng_get_random_bytes(uint8 * pu8PRNGBuff,uint16 u16PRNGSize) + * @param [in] pu8PrngBuff + * Pointer to Buffer to receive data. + * Size greater than the maximum specified (@ref M2M_BUFFER_MAX_SIZE - sizeof(tstrPrng)) + * causes a negative error @ref M2M_ERR_FAIL. + * @param [in] u16PrngSize + request size in bytes + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +sint8 m2m_wifi_prng_get_random_bytes(uint8 * pu8PrngBuff,uint16 u16PrngSize); +#ifdef __cplusplus +} +#endif +#endif /* __M2M_WIFI_H__ */ + diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_ate_mode.c b/ext/drivers/atmel/winc1500/driver/source/m2m_ate_mode.c new file mode 100755 index 0000000000000..4a2d013ec8802 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_ate_mode.c @@ -0,0 +1,797 @@ +/** + * + * \file + * + * \brief NMC1500 Peripherials Application Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifdef _M2M_ATE_FW_ +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#include "driver/include/m2m_ate_mode.h" +#include "driver/source/nmasic.h" +#include "driver/source/nmdrv.h" +#include "m2m_hif.h" +#include "driver/source/nmbus.h" +#include "bsp/include/nm_bsp.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#define rInterrupt_CORTUS_0 (0x10a8) +#define rInterrupt_CORTUS_1 (0x10ac) +#define rInterrupt_CORTUS_2 (0x10b0) + +#define rBurstTx_NMI_TX_RATE (0x161d00) +#define rBurstTx_NMI_NUM_TX_FRAMES (0x161d04) +#define rBurstTx_NMI_TX_FRAME_LEN (0x161d08) +#define rBurstTx_NMI_TX_CW_PARAM (0x161d0c) +#define rBurstTx_NMI_TX_GAIN (0x161d10) +#define rBurstTx_NMI_TX_DPD_CTRL (0x161d14) +#define rBurstTx_NMI_USE_PMU (0x161d18) +#define rBurstTx_NMI_TEST_CH (0x161d1c) +#define rBurstTx_NMI_TX_PHY_CONT (0x161d20) +#define rBurstTx_NMI_TX_CW_MODE (0x161d24) +#define rBurstTx_NMI_TEST_XO_OFF (0x161d28) +#define rBurstTx_NMI_USE_EFUSE_XO_OFF (0x161d2c) + +#define rBurstTx_NMI_MAC_FILTER_ENABLE_DA (0x161d30) +#define rBurstTx_NMI_MAC_ADDR_LO_PEER (0x161d34) +#define rBurstTx_NMI_MAC_ADDR_LO_SELF (0x161d38) +#define rBurstTx_NMI_MAC_ADDR_HI_PEER (0x161d3c) +#define rBurstTx_NMI_MAC_ADDR_HI_SELF (0x161d40) +#define rBurstTx_NMI_RX_PKT_CNT_SUCCESS (0x161d44) +#define rBurstTx_NMI_RX_PKT_CNT_FAIL (0x161d48) +#define rBurstTx_NMI_SET_SELF_MAC_ADDR (0x161d4c) +#define rBurstTx_NMI_MAC_ADDR_LO_SA (0x161d50) +#define rBurstTx_NMI_MAC_ADDR_HI_SA (0x161d54) +#define rBurstTx_NMI_MAC_FILTER_ENABLE_SA (0x161d58) + +#define rBurstRx_NMI_RX_ALL_PKTS_CONT (0x9898) +#define rBurstRx_NMI_RX_ERR_PKTS_CONT (0x988c) + +#define TX_DGAIN_MAX_NUM_REGS (4) +#define TX_DGAIN_REG_BASE_ADDRESS (0x1240) +#define TX_GAIN_CODE_MAX_NUM_REGS (3) +#define TX_GAIN_CODE_BASE_ADDRESS (0x1250) +#define TX_PA_MAX_NUM_REGS (3) +#define TX_PA_BASE_ADDRESS (0x1e58) +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +VARIABLES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +volatile static uint8 gu8AteIsRunning = 0; /*!< ATE firmware status, 1 means ATE is running otherwise stopped */ +volatile static uint8 gu8RxState = 0; /*!< RX status, 1 means Rx is running otherwise stopped */ +volatile static uint8 gu8TxState = 0; /*!< TX status, 1 means Tx is running otherwise stopped */ +volatile static uint32 gaAteFwTxRates[M2M_ATE_MAX_NUM_OF_RATES] = +{ + 0x01, 0x02, 0x05, 0x0B, /*B-Rats*/ + 0x06, 0x09, 0x0C, 0x12, 0x18, 0x24, 0x30, 0x36, /*G-Rats*/ + 0x80, 0x81, 0x82, 0x83, 0x84, 0x85, 0x86, 0x87 /*N-Rats*/ +}; + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +STATIC FUNCTIONS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +static void m2m_ate_set_rx_status(uint8 u8Value) +{ + gu8RxState = u8Value; +} + +static void m2m_ate_set_tx_status(uint8 u8Value) +{ + gu8TxState = u8Value; +} + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION IMPLEMENTATION +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/*! +@fn \ + sint8 m2m_ate_init(void); + +@brief + This function used to download ATE firmware from flash and start it + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_init(void) +{ + sint8 s8Ret = M2M_SUCCESS; + uint8 u8WifiMode = M2M_WIFI_MODE_ATE_HIGH; + + s8Ret = nm_drv_init(&u8WifiMode); + + return s8Ret; +} + +/*! +@fn \ + sint8 m2m_ate_init(tstrM2mAteInit *pstrInit); + +@brief + This function used to download ATE firmware from flash and start it + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_init_param(tstrM2mAteInit *pstrInit) +{ + sint8 s8Ret = M2M_SUCCESS; + + s8Ret = nm_drv_init((void*)&pstrInit->u8RxPwrMode); + + return s8Ret; +} + +/*! +@fn \ + sint8 m2m_ate_deinit(void); + +@brief + De-Initialization of ATE firmware mode + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_deinit(void) +{ + return nm_drv_deinit(NULL); +} + +/*! +@fn \ + sint8 m2m_ate_set_fw_state(uint8); + +@brief + This function used to change ATE firmware status from running to stopped or vice versa. + +@param [in] u8State + Required state of ATE firmware, one of \ref tenuM2mAteFwState enumeration values. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init +*/ +sint8 m2m_ate_set_fw_state(uint8 u8State) +{ + sint8 s8Ret = M2M_SUCCESS; + uint32_t u32Val = 0; + + if((M2M_ATE_FW_STATE_STOP == u8State) && (M2M_ATE_FW_STATE_STOP != gu8AteIsRunning)) + { + u32Val = nm_read_reg(rNMI_GLB_RESET); + u32Val &= ~(1 << 10); + s8Ret = nm_write_reg(rNMI_GLB_RESET, u32Val); + gu8AteIsRunning = M2M_ATE_FW_STATE_STOP; + } + else if((M2M_ATE_FW_STATE_RUN == u8State) && (M2M_ATE_FW_STATE_RUN != gu8AteIsRunning)) + { + /* 0x1118[0]=0 at power-on-reset: pad-based control. */ + /* Switch cortus reset register to register control. 0x1118[0]=1. */ + u32Val = nm_read_reg(rNMI_BOOT_RESET_MUX); + u32Val |= (1 << 0); + s8Ret = nm_write_reg(rNMI_BOOT_RESET_MUX, u32Val); + if(M2M_SUCCESS != s8Ret) + { + goto __EXIT; + } + /** + Write the firmware download complete magic value 0x10ADD09E at + location 0xFFFF000C (Cortus map) or C000C (AHB map). + This will let the boot-rom code execute from RAM. + **/ + s8Ret = nm_write_reg(0xc0000, 0x71); + if(M2M_SUCCESS != s8Ret) + { + goto __EXIT; + } + + u32Val = nm_read_reg(rNMI_GLB_RESET); + if((u32Val & (1ul << 10)) == (1ul << 10)) + { + u32Val &= ~(1ul << 10); + s8Ret = nm_write_reg(rNMI_GLB_RESET, u32Val); + if(M2M_SUCCESS != s8Ret) + { + goto __EXIT; + } + } + + u32Val |= (1ul << 10); + s8Ret = nm_write_reg(rNMI_GLB_RESET, u32Val); + if(M2M_SUCCESS != s8Ret) + { + goto __EXIT; + } + gu8AteIsRunning = M2M_ATE_FW_STATE_RUN; + } + else + { + s8Ret = M2M_ATE_ERR_UNHANDLED_CASE; + } + +__EXIT: + if((M2M_SUCCESS == s8Ret) && (M2M_ATE_FW_STATE_RUN == gu8AteIsRunning)) + { + nm_bsp_sleep(500); /*wait for ATE firmware start up*/ + } + return s8Ret; +} + +/*! +@fn \ + sint8 m2m_ate_get_fw_state(uint8); + +@brief + This function used to return status of ATE firmware. + +@return + The function SHALL return status of ATE firmware, one of \ref tenuM2mAteFwState enumeration values. +\sa + m2m_ate_init, m2m_ate_set_fw_state +*/ +sint8 m2m_ate_get_fw_state(void) +{ + return gu8AteIsRunning; +} + +/*! +@fn \ + uint32 m2m_ate_get_tx_rate(uint8); + +@brief + This function used to return value of TX rate required by application developer. + +@param [in] u8Index + Index of required rate , one of \ref tenuM2mAteTxIndexOfRates enumeration values. +@return + The function SHALL return 0 for in case of failure otherwise selected rate value. +\sa + tenuM2mAteTxIndexOfRates +*/ +uint32 m2m_ate_get_tx_rate(uint8 u8Index) +{ + if(M2M_ATE_MAX_NUM_OF_RATES <= u8Index) + { + return 0; + } + return gaAteFwTxRates[u8Index]; +} + +/*! +@fn \ + sint8 m2m_ate_get_tx_status(void); + +@brief + This function used to return status of TX test case either running or stopped. + +@return + The function SHALL return status of ATE firmware, 1 if TX is running otherwise 0. +\sa + m2m_ate_start_tx, m2m_ate_stop_tx +*/ +sint8 m2m_ate_get_tx_status(void) +{ + return gu8TxState; +} + +/*! +@fn \ + sint8 m2m_ate_start_tx(tstrM2mAteTx *) + +@brief + This function used to start TX test case. + +@param [in] strM2mAteTx + Type of \ref tstrM2mAteTx, with the values required to enable TX test case. You must use \ref m2m_ate_init first. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_stop_tx, m2m_ate_get_tx_status +*/ +sint8 m2m_ate_start_tx(tstrM2mAteTx * strM2mAteTx) +{ + sint8 s8Ret = M2M_SUCCESS; + uint8 u8LoopCntr = 0; + uint32_t val32; + + + if(NULL == strM2mAteTx) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + if(0 != m2m_ate_get_tx_status()) + { + s8Ret = M2M_ATE_ERR_TX_ALREADY_RUNNING; + goto __EXIT; + } + + if(0 != m2m_ate_get_rx_status()) + { + s8Ret = M2M_ATE_ERR_RX_ALREADY_RUNNING; + goto __EXIT; + } + + if( (strM2mAteTx->channel_num < M2M_ATE_CHANNEL_1) || + (strM2mAteTx->channel_num > M2M_ATE_CHANNEL_14) || + (strM2mAteTx->tx_gain_sel < M2M_ATE_TX_GAIN_DYNAMIC) || + (strM2mAteTx->tx_gain_sel > M2M_ATE_TX_GAIN_TELEC) || + (strM2mAteTx->frame_len > M2M_ATE_MAX_FRAME_LENGTH) || + (strM2mAteTx->frame_len < M2M_ATE_MIN_FRAME_LENGTH) + ) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + if( (strM2mAteTx->duty_cycle < M2M_ATE_TX_DUTY_MAX_VALUE /*1*/) || + (strM2mAteTx->duty_cycle > M2M_ATE_TX_DUTY_MIN_VALUE /*10*/ ) || + (strM2mAteTx->dpd_ctrl < M2M_ATE_TX_DPD_DYNAMIC) || + (strM2mAteTx->dpd_ctrl > M2M_ATE_TX_DPD_ENABLED) || + (strM2mAteTx->use_pmu < M2M_ATE_PMU_DISBLE) || + (strM2mAteTx->use_pmu > M2M_ATE_PMU_ENABLE) || + (strM2mAteTx->phy_burst_tx < M2M_ATE_TX_SRC_MAC) || + (strM2mAteTx->phy_burst_tx > M2M_ATE_TX_SRC_PHY) || + (strM2mAteTx->cw_tx < M2M_ATE_TX_MODE_NORM) || + (strM2mAteTx->cw_tx > M2M_ATE_TX_MODE_CW) + ) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + for(u8LoopCntr=0; u8LoopCntrdata_rate) + { + break; + } + } + + if(M2M_ATE_MAX_NUM_OF_RATES == u8LoopCntr) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + s8Ret += nm_write_reg(rBurstTx_NMI_USE_PMU, strM2mAteTx->use_pmu); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_PHY_CONT, strM2mAteTx->phy_burst_tx); + s8Ret += nm_write_reg(rBurstTx_NMI_NUM_TX_FRAMES, strM2mAteTx->num_frames); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_GAIN, strM2mAteTx->tx_gain_sel); + s8Ret += nm_write_reg(rBurstTx_NMI_TEST_CH, strM2mAteTx->channel_num); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_FRAME_LEN, strM2mAteTx->frame_len); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_CW_PARAM, strM2mAteTx->duty_cycle); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_DPD_CTRL, strM2mAteTx->dpd_ctrl); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_RATE, strM2mAteTx->data_rate); + s8Ret += nm_write_reg(rBurstTx_NMI_TX_CW_MODE, strM2mAteTx->cw_tx); + s8Ret += nm_write_reg(rBurstTx_NMI_TEST_XO_OFF, strM2mAteTx->xo_offset_x1000); + s8Ret += nm_write_reg(rBurstTx_NMI_USE_EFUSE_XO_OFF, strM2mAteTx->use_efuse_xo_offset); + + val32 = strM2mAteTx->peer_mac_addr[5] << 0; + val32 |= strM2mAteTx->peer_mac_addr[4] << 8; + val32 |= strM2mAteTx->peer_mac_addr[3] << 16; + nm_write_reg(rBurstTx_NMI_MAC_ADDR_LO_PEER, val32 ); + + val32 = strM2mAteTx->peer_mac_addr[2] << 0; + val32 |= strM2mAteTx->peer_mac_addr[1] << 8; + val32 |= strM2mAteTx->peer_mac_addr[0] << 16; + nm_write_reg(rBurstTx_NMI_MAC_ADDR_HI_PEER, val32 ); + + if(M2M_SUCCESS == s8Ret) + { + s8Ret += nm_write_reg(rInterrupt_CORTUS_0, 1); /*Interrupt Cortus*/ + m2m_ate_set_tx_status(1); + nm_bsp_sleep(200); /*Recommended*/ + } + +__EXIT: + return s8Ret; +} + +/*! +@fn \ + sint8 m2m_ate_stop_tx(void) + +@brief + This function used to stop TX test case. + +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_start_tx, m2m_ate_get_tx_status +*/ +sint8 m2m_ate_stop_tx(void) +{ + sint8 s8Ret = M2M_SUCCESS; + + s8Ret = nm_write_reg(rInterrupt_CORTUS_1, 1); + if(M2M_SUCCESS == s8Ret) + { + m2m_ate_set_tx_status(0); + } + + return s8Ret; +} + +/*! +@fn \ + sint8 m2m_ate_get_rx_status(uint8); + +@brief + This function used to return status of RX test case either running or stopped. + +@return + The function SHALL return status of ATE firmware, 1 if RX is running otherwise 0. +\sa + m2m_ate_start_rx, m2m_ate_stop_rx +*/ +sint8 m2m_ate_get_rx_status(void) +{ + return gu8RxState; +} + +/*! +@fn \ + sint8 m2m_ate_start_rx(tstrM2mAteRx *) + +@brief + This function used to start RX test case. + +@param [in] strM2mAteRx + Type of \ref tstrM2mAteRx, with the values required to enable RX test case. You must use \ref m2m_ate_init first. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_stop_rx, m2m_ate_get_rx_status +*/ +sint8 m2m_ate_start_rx(tstrM2mAteRx * strM2mAteRxStr) +{ + sint8 s8Ret = M2M_SUCCESS; + uint32 val32; + if(NULL == strM2mAteRxStr) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + if(0 != m2m_ate_get_tx_status()) + { + s8Ret = M2M_ATE_ERR_TX_ALREADY_RUNNING; + goto __EXIT; + } + + if(0 != m2m_ate_get_rx_status()) + { + s8Ret = M2M_ATE_ERR_RX_ALREADY_RUNNING; + goto __EXIT; + } + + if( (strM2mAteRxStr->channel_num < M2M_ATE_CHANNEL_1) || + (strM2mAteRxStr->channel_num > M2M_ATE_CHANNEL_14)|| + (strM2mAteRxStr->use_pmu < M2M_ATE_PMU_DISBLE) || + (strM2mAteRxStr->use_pmu > M2M_ATE_PMU_ENABLE) + ) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + s8Ret += nm_write_reg(rBurstTx_NMI_TEST_CH, strM2mAteRxStr->channel_num); + s8Ret += nm_write_reg(rBurstTx_NMI_USE_PMU, strM2mAteRxStr->use_pmu); + s8Ret += nm_write_reg(rBurstTx_NMI_TEST_XO_OFF, strM2mAteRxStr->xo_offset_x1000); + s8Ret += nm_write_reg(rBurstTx_NMI_USE_EFUSE_XO_OFF, strM2mAteRxStr->use_efuse_xo_offset); + + if(strM2mAteRxStr->override_self_mac_addr) + { + val32 = strM2mAteRxStr->self_mac_addr[5] << 0; + val32 |= strM2mAteRxStr->self_mac_addr[4] << 8; + val32 |= strM2mAteRxStr->self_mac_addr[3] << 16; + nm_write_reg(rBurstTx_NMI_MAC_ADDR_LO_SELF, val32 ); + + val32 = strM2mAteRxStr->self_mac_addr[2] << 0; + val32 |= strM2mAteRxStr->self_mac_addr[1] << 8; + val32 |= strM2mAteRxStr->self_mac_addr[0] << 16; + nm_write_reg(rBurstTx_NMI_MAC_ADDR_HI_SELF, val32 ); + } + + if(strM2mAteRxStr->mac_filter_en_sa) + { + val32 = strM2mAteRxStr->peer_mac_addr[5] << 0; + val32 |= strM2mAteRxStr->peer_mac_addr[4] << 8; + val32 |= strM2mAteRxStr->peer_mac_addr[3] << 16; + nm_write_reg(rBurstTx_NMI_MAC_ADDR_LO_SA, val32 ); + + val32 = strM2mAteRxStr->peer_mac_addr[2] << 0; + val32 |= strM2mAteRxStr->peer_mac_addr[1] << 8; + val32 |= strM2mAteRxStr->peer_mac_addr[0] << 16; + nm_write_reg(rBurstTx_NMI_MAC_ADDR_HI_SA, val32 ); + } + + nm_write_reg(rBurstTx_NMI_MAC_FILTER_ENABLE_DA, strM2mAteRxStr->mac_filter_en_da); + nm_write_reg(rBurstTx_NMI_MAC_FILTER_ENABLE_SA, strM2mAteRxStr->mac_filter_en_sa); + nm_write_reg(rBurstTx_NMI_SET_SELF_MAC_ADDR, strM2mAteRxStr->override_self_mac_addr); + + if(M2M_SUCCESS == s8Ret) + { + s8Ret += nm_write_reg(rInterrupt_CORTUS_2, 1); /*Interrupt Cortus*/ + m2m_ate_set_rx_status(1); + nm_bsp_sleep(10); /*Recommended*/ + } + +__EXIT: + return s8Ret; +} + +/*! +@fn \ + sint8 m2m_ate_stop_rx(void) + +@brief + This function used to stop RX test case. + +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_start_rx, m2m_ate_get_rx_status +*/ +sint8 m2m_ate_stop_rx(void) +{ + m2m_ate_set_rx_status(0); + nm_bsp_sleep(200); /*Recommended*/ + return M2M_SUCCESS; +} + +/*! +@fn \ + sint8 m2m_ate_read_rx_status(tstrM2mAteRxStatus *) + +@brief + This function used to read RX statistics from ATE firmware. + +@param [out] strM2mAteRxStatus + Type of \ref tstrM2mAteRxStatus used to save statistics of RX test case. You must use \ref m2m_ate_start_rx first. +@return + The function SHALL return 0 for success and a negative value otherwise. +\sa + m2m_ate_init, m2m_ate_start_rx +*/ +sint8 m2m_ate_read_rx_status(tstrM2mAteRxStatus *strM2mAteRxStatus) +{ + sint8 s8Ret = M2M_SUCCESS; + + if(NULL == strM2mAteRxStatus) + { + s8Ret = M2M_ATE_ERR_VALIDATE; + goto __EXIT; + } + + if(0 != m2m_ate_get_tx_status()) + { + s8Ret = M2M_ATE_ERR_TX_ALREADY_RUNNING; + goto __EXIT; + } + + if (nm_read_reg(rBurstTx_NMI_MAC_FILTER_ENABLE_DA) || nm_read_reg(rBurstTx_NMI_MAC_FILTER_ENABLE_SA)) + { + strM2mAteRxStatus->num_rx_pkts = nm_read_reg(rBurstTx_NMI_RX_PKT_CNT_SUCCESS) + nm_read_reg(rBurstTx_NMI_RX_PKT_CNT_FAIL); + strM2mAteRxStatus->num_good_pkts = nm_read_reg(rBurstTx_NMI_RX_PKT_CNT_SUCCESS); + strM2mAteRxStatus->num_err_pkts = nm_read_reg(rBurstTx_NMI_RX_PKT_CNT_FAIL); + } + else + { + strM2mAteRxStatus->num_rx_pkts = nm_read_reg(rBurstRx_NMI_RX_ALL_PKTS_CONT) + nm_read_reg(0x989c); + strM2mAteRxStatus->num_err_pkts = nm_read_reg(rBurstRx_NMI_RX_ERR_PKTS_CONT); + strM2mAteRxStatus->num_good_pkts = strM2mAteRxStatus->num_rx_pkts - strM2mAteRxStatus->num_err_pkts; + } + +__EXIT: + return s8Ret; +} +/*! +@fn \ + sint8 m2m_ate_set_dig_gain(double dGaindB) + +@brief + This function is used to set the digital gain + +@param [in] double dGaindB + The digital gain value required to be set. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_set_dig_gain(double dGaindB) +{ + uint32_t dGain, val32; + dGain = (uint32_t)(pow(10, dGaindB/20.0) * 1024.0); + + val32 = nm_read_reg(0x160cd0); + val32 &= ~(0x1ffful << 0); + val32 |= (((uint32_t)dGain) << 0); + nm_write_reg(0x160cd0, val32); + return M2M_SUCCESS; +} +/*! +@fn \ + sint8 m2m_ate_get_dig_gain(double * dGaindB) + +@brief + This function is used to get the digital gain + +@param [out] double * dGaindB + The retrieved digital gain value obtained from HW registers in dB. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_dig_gain(double * dGaindB) +{ + uint32 dGain, val32; + + if(!dGaindB) return M2M_ERR_INVALID_ARG; + + val32 = nm_read_reg(0x160cd0); + + dGain = (val32 >> 0) & 0x1ffful; + *dGaindB = 20.0*log10((double)dGain / 1024.0); + + return M2M_SUCCESS; +} +/*! +@fn \ + sint8 m2m_ate_get_pa_gain(double *paGaindB) + +@brief + This function is used to get the PA gain + +@param [out] double *paGaindB + The retrieved PA gain value obtained from HW registers in dB. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_pa_gain(double *paGaindB) +{ + uint32 val32, paGain; + uint32 m_cmbPAGainStep; + + if(!paGaindB) + return M2M_ERR_INVALID_ARG; + + val32 = nm_read_reg(0x1e9c); + + paGain = (val32 >> 8) & 0x3f; + + switch(paGain){ + case 0x1: + m_cmbPAGainStep = 5; + break; + case 0x3: + m_cmbPAGainStep = 4; + break; + case 0x7: + m_cmbPAGainStep = 3; + break; + case 0xf: + m_cmbPAGainStep = 2; + break; + case 0x1f: + m_cmbPAGainStep = 1; + break; + case 0x3f: + m_cmbPAGainStep = 0; + break; + default: + m_cmbPAGainStep = 0; + break; + } + + *paGaindB = 18 - m_cmbPAGainStep*3; + + return M2M_SUCCESS; +} +/*! +@fn \ + sint8 m2m_ate_get_ppa_gain(double * ppaGaindB) + +@brief + This function is used to get the PPA gain + +@param [out] uint32 * ppaGaindB + The retrieved PPA gain value obtained from HW registers in dB. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_ppa_gain(double * ppaGaindB) +{ + uint32 val32, ppaGain, m_cmbPPAGainStep; + + if(!ppaGaindB) return M2M_ERR_INVALID_ARG; + + val32 = nm_read_reg(0x1ea0); + + ppaGain = (val32 >> 5) & 0x7; + + switch(ppaGain){ + case 0x1: + m_cmbPPAGainStep = 2; + break; + case 0x3: + m_cmbPPAGainStep = 1; + break; + case 0x7: + m_cmbPPAGainStep = 0; + break; + default: + m_cmbPPAGainStep = 3; + break; + } + + *ppaGaindB = 9 - m_cmbPPAGainStep*3; + + + return M2M_SUCCESS; +} +/*! +@fn \ + sint8 m2m_ate_get_tot_gain(double * totGaindB) + +@brief + This function is used to calculate the total gain + +@param [out] double * totGaindB + The retrieved total gain value obtained from calculations made based on the digital gain, PA and PPA gain values. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +sint8 m2m_ate_get_tot_gain(double * totGaindB) +{ + double dGaindB, paGaindB, ppaGaindB; + + if(!totGaindB) return M2M_ERR_INVALID_ARG; + + m2m_ate_get_pa_gain(&paGaindB); + m2m_ate_get_ppa_gain(&ppaGaindB); + m2m_ate_get_dig_gain(&dGaindB); + + *totGaindB = dGaindB + paGaindB + ppaGaindB; + + return M2M_SUCCESS; +} + +#endif //_M2M_ATE_FW_ \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_crypto.c b/ext/drivers/atmel/winc1500/driver/source/m2m_crypto.c new file mode 100755 index 0000000000000..9ac7711309552 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_crypto.c @@ -0,0 +1,1010 @@ +/** + * + * \file + * + * \brief WINC Crypto module. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "driver/include/m2m_crypto.h" +#include "driver/source/nmbus.h" +#include "driver/source/nmasic.h" + +#ifdef CONF_CRYPTO_HW + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*======*======*======*======*======*=======* +* WINC SHA256 HW Engine Register Definition * +*======*======*======*======*======*========*/ + +#define SHA_BLOCK_SIZE (64) + +#define SHARED_MEM_BASE (0xd0000) + + +#define SHA256_MEM_BASE (0x180000UL) +#define SHA256_ENGINE_ADDR (0x180000ul) + +/* SHA256 Registers */ +#define SHA256_CTRL (SHA256_MEM_BASE+0x00) +#define SHA256_CTRL_START_CALC_MASK (NBIT0) +#define SHA256_CTRL_START_CALC_SHIFT (0) +#define SHA256_CTRL_PREPROCESS_MASK (NBIT1) +#define SHA256_CTRL_PREPROCESS_SHIFT (1) +#define SHA256_CTRL_HASH_HASH_MASK (NBIT2) +#define SHA256_CTRL_HASH_HASH_SHIFT (2) +#define SHA256_CTRL_INIT_SHA256_STATE_MASK (NBIT3) +#define SHA256_CTRL_INIT_SHA256_STATE_SHIFT (3) +#define SHA256_CTRL_WR_BACK_HASH_VALUE_MASK (NBIT4) +#define SHA256_CTRL_WR_BACK_HASH_VALUE_SHIFT (4) +#define SHA256_CTRL_FORCE_SHA256_QUIT_MASK (NBIT5) +#define SHA256_CTRL_FORCE_SHA256_QUIT_SHIFT (5) + +#define SHA256_REGS_SHA256_CTRL_AHB_BYTE_REV_EN (NBIT6) +#define SHA256_REGS_SHA256_CTRL_RESERVED (NBIT7) +#define SHA256_REGS_SHA256_CTRL_CORE_TO_AHB_CLK_RATIO (NBIT8+ NBIT9+ NBIT10) +#define SHA256_REGS_SHA256_CTRL_CORE_TO_AHB_CLK_RATIO_MASK (NBIT2+ NBIT1+ NBIT0) +#define SHA256_REGS_SHA256_CTRL_CORE_TO_AHB_CLK_RATIO_SHIFT (8) +#define SHA256_REGS_SHA256_CTRL_RESERVED_11 (NBIT11) +#define SHA256_REGS_SHA256_CTRL_SHA1_CALC (NBIT12) +#define SHA256_REGS_SHA256_CTRL_PBKDF2_SHA1_CALC (NBIT13) + + +#define SHA256_START_RD_ADDR (SHA256_MEM_BASE+0x04UL) +#define SHA256_DATA_LENGTH (SHA256_MEM_BASE+0x08UL) +#define SHA256_START_WR_ADDR (SHA256_MEM_BASE+0x0cUL) +#define SHA256_COND_CHK_CTRL (SHA256_MEM_BASE+0x10) +#define SHA256_COND_CHK_CTRL_HASH_VAL_COND_CHK_MASK (NBIT1 | NBIT0) +#define SHA256_COND_CHK_CTRL_HASH_VAL_COND_CHK_SHIFT (0) +#define SHA256_COND_CHK_CTRL_STEP_VAL_MASK (NBIT6 | NBIT5 | NBIT4 | NBIT3 | NBIT2) +#define SHA256_COND_CHK_CTRL_STEP_VAL_SHIFT (2) +#define SHA256_COND_CHK_CTRL_COND_CHK_RESULT_MASK (NBIT7) +#define SHA256_COND_CHK_CTRL_COND_CHK_RESULT_SHIFT (7) + +#define SHA256_MOD_DATA_RANGE (SHA256_MEM_BASE+0x14) +#define SHA256_MOD_DATA_RANGE_ST_BYTE_2_ADD_STP_MASK (NBIT24-1) +#define SHA256_MOD_DATA_RANGE_ST_BYTE_2_ADD_STP_SHIFT (0) +#define SHA256_MOD_DATA_RANGE_MOD_DATA_LEN_MASK (NBIT24 | NBIT25| NBIT26) +#define SHA256_MOD_DATA_RANGE_MOD_DATA_LEN_SHIFT (24) + + +#define SHA256_COND_CHK_STS_1 (SHA256_MEM_BASE+0x18) +#define SHA256_COND_CHK_STS_2 (SHA256_MEM_BASE+0x1c) +#define SHA256_DONE_INTR_ENABLE (SHA256_MEM_BASE+0x20) +#define SHA256_DONE_INTR_STS (SHA256_MEM_BASE+0x24) +#define SHA256_TARGET_HASH_H1 (SHA256_MEM_BASE+0x28) +#define SHA256_TARGET_HASH_H2 (SHA256_MEM_BASE+0x2c) +#define SHA256_TARGET_HASH_H3 (SHA256_MEM_BASE+0x30) +#define SHA256_TARGET_HASH_H4 (SHA256_MEM_BASE+0x34) +#define SHA256_TARGET_HASH_H5 (SHA256_MEM_BASE+0x38) +#define SHA256_TARGET_HASH_H6 (SHA256_MEM_BASE+0x3c) +#define SHA256_TARGET_HASH_H7 (SHA256_MEM_BASE+0x40) +#define SHA256_TARGET_HASH_H8 (SHA256_MEM_BASE+0x44) + +/*======*======*======*======*======*=======* +* WINC BIGINT HW Engine Register Definition * +*======*======*======*======*======*========*/ + + +#define BIGINT_ENGINE_ADDR (0x180080ul) +#define BIGINT_VERSION (BIGINT_ENGINE_ADDR + 0x00) + +#define BIGINT_MISC_CTRL (BIGINT_ENGINE_ADDR + 0x04) +#define BIGINT_MISC_CTRL_CTL_START (NBIT0) +#define BIGINT_MISC_CTRL_CTL_RESET (NBIT1) +#define BIGINT_MISC_CTRL_CTL_MSW_FIRST (NBIT2) +#define BIGINT_MISC_CTRL_CTL_SWAP_BYTE_ORDER (NBIT3) +#define BIGINT_MISC_CTRL_CTL_FORCE_BARRETT (NBIT4) +#define BIGINT_MISC_CTRL_CTL_M_PRIME_VALID (NBIT5) + +#define BIGINT_M_PRIME (BIGINT_ENGINE_ADDR + 0x08) + +#define BIGINT_STATUS (BIGINT_ENGINE_ADDR + 0x0C) +#define BIGINT_STATUS_STS_DONE (NBIT0) + +#define BIGINT_CLK_COUNT (BIGINT_ENGINE_ADDR + 0x10) +#define BIGINT_ADDR_X (BIGINT_ENGINE_ADDR + 0x14) +#define BIGINT_ADDR_E (BIGINT_ENGINE_ADDR + 0x18) +#define BIGINT_ADDR_M (BIGINT_ENGINE_ADDR + 0x1C) +#define BIGINT_ADDR_R (BIGINT_ENGINE_ADDR + 0x20) +#define BIGINT_LENGTH (BIGINT_ENGINE_ADDR + 0x24) + +#define BIGINT_IRQ_STS (BIGINT_ENGINE_ADDR + 0x28) +#define BIGINT_IRQ_STS_DONE (NBIT0) +#define BIGINT_IRQ_STS_CHOOSE_MONT (NBIT1) +#define BIGINT_IRQ_STS_M_READ (NBIT2) +#define BIGINT_IRQ_STS_X_READ (NBIT3) +#define BIGINT_IRQ_STS_START (NBIT4) +#define BIGINT_IRQ_STS_PRECOMP_FINISH (NBIT5) + +#define BIGINT_IRQ_MASK (BIGINT_ENGINE_ADDR + 0x2C) +#define BIGINT_IRQ_MASK_CTL_IRQ_MASK_START (NBIT4) + +#define ENABLE_FLIPPING 1 + + + + +#define GET_UINT32(BUF,OFFSET) (((uint32)((BUF)[OFFSET])) | ((uint32)(((BUF)[OFFSET + 1]) << 8)) | \ +((uint32)(((BUF)[OFFSET + 2]) << 16)) | ((uint32)(((BUF)[OFFSET + 3]) << 24))) + +#define PUTU32(VAL32,BUF,OFFSET) \ +do \ +{ \ + (BUF)[OFFSET ] = BYTE_3((VAL32)); \ + (BUF)[OFFSET +1 ] = BYTE_2((VAL32)); \ + (BUF)[OFFSET +2 ] = BYTE_1((VAL32)); \ + (BUF)[OFFSET +3 ] = BYTE_0((VAL32)); \ +}while(0) + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*! +@struct \ + tstrHashContext + +@brief +*/ +typedef struct{ + uint32 au32HashState[M2M_SHA256_DIGEST_LEN/4]; + uint8 au8CurrentBlock[64]; + uint32 u32TotalLength; + uint8 u8InitHashFlag; +}tstrSHA256HashCtxt; + + + +/*======*======*======*======*======*=======* +* SHA256 IMPLEMENTATION * +*======*======*======*======*======*========*/ + +sint8 m2m_crypto_sha256_hash_init(tstrM2mSha256Ctxt *pstrSha256Ctxt) +{ + tstrSHA256HashCtxt *pstrSHA256 = (tstrSHA256HashCtxt*)pstrSha256Ctxt; + if(pstrSHA256 != NULL) + { + m2m_memset((uint8*)pstrSha256Ctxt, 0, sizeof(tstrM2mSha256Ctxt)); + pstrSHA256->u8InitHashFlag = 1; + } + return 0; +} + +sint8 m2m_crypto_sha256_hash_update(tstrM2mSha256Ctxt *pstrSha256Ctxt, uint8 *pu8Data, uint16 u16DataLength) +{ + sint8 s8Ret = M2M_ERR_FAIL; + tstrSHA256HashCtxt *pstrSHA256 = (tstrSHA256HashCtxt*)pstrSha256Ctxt; + if(pstrSHA256 != NULL) + { + uint32 u32ReadAddr; + uint32 u32WriteAddr = SHARED_MEM_BASE; + uint32 u32Addr = u32WriteAddr; + uint32 u32ResidualBytes; + uint32 u32NBlocks; + uint32 u32Offset; + uint32 u32CurrentBlock = 0; + uint8 u8IsDone = 0; + + /* Get the remaining bytes from the previous update (if the length is not block aligned). */ + u32ResidualBytes = pstrSHA256->u32TotalLength % SHA_BLOCK_SIZE; + + /* Update the total data length. */ + pstrSHA256->u32TotalLength += u16DataLength; + + if(u32ResidualBytes != 0) + { + if((u32ResidualBytes + u16DataLength) >= SHA_BLOCK_SIZE) + { + u32Offset = SHA_BLOCK_SIZE - u32ResidualBytes; + m2m_memcpy(&pstrSHA256->au8CurrentBlock[u32ResidualBytes], pu8Data, u32Offset); + pu8Data += u32Offset; + u16DataLength -= u32Offset; + + nm_write_block(u32Addr, pstrSHA256->au8CurrentBlock, SHA_BLOCK_SIZE); + u32Addr += SHA_BLOCK_SIZE; + u32CurrentBlock = 1; + } + else + { + m2m_memcpy(&pstrSHA256->au8CurrentBlock[u32ResidualBytes], pu8Data, u16DataLength); + u16DataLength = 0; + } + } + + /* Get the number of HASH BLOCKs and the residual bytes. */ + u32NBlocks = u16DataLength / SHA_BLOCK_SIZE; + u32ResidualBytes = u16DataLength % SHA_BLOCK_SIZE; + + if(u32NBlocks != 0) + { + nm_write_block(u32Addr, pu8Data, (uint16)(u32NBlocks * SHA_BLOCK_SIZE)); + pu8Data += (u32NBlocks * SHA_BLOCK_SIZE); + } + + u32NBlocks += u32CurrentBlock; + if(u32NBlocks != 0) + { + uint32 u32RegVal = 0; + + nm_write_reg(SHA256_CTRL, u32RegVal); + u32RegVal |= SHA256_CTRL_FORCE_SHA256_QUIT_MASK; + nm_write_reg(SHA256_CTRL, u32RegVal); + + if(pstrSHA256->u8InitHashFlag) + { + pstrSHA256->u8InitHashFlag = 0; + u32RegVal |= SHA256_CTRL_INIT_SHA256_STATE_MASK; + } + + u32ReadAddr = u32WriteAddr + (u32NBlocks * SHA_BLOCK_SIZE); + nm_write_reg(SHA256_DATA_LENGTH, (u32NBlocks * SHA_BLOCK_SIZE)); + nm_write_reg(SHA256_START_RD_ADDR, u32WriteAddr); + nm_write_reg(SHA256_START_WR_ADDR, u32ReadAddr); + + u32RegVal |= SHA256_CTRL_START_CALC_MASK; + + u32RegVal &= ~(0x7 << 8); + u32RegVal |= (2 << 8); + + nm_write_reg(SHA256_CTRL, u32RegVal); + + /* 5. Wait for done_intr */ + while(!u8IsDone) + { + u32RegVal = nm_read_reg(SHA256_DONE_INTR_STS); + u8IsDone = u32RegVal & NBIT0; + } + } + if(u32ResidualBytes != 0) + { + m2m_memcpy(pstrSHA256->au8CurrentBlock, pu8Data, u32ResidualBytes); + } + s8Ret = M2M_SUCCESS; + } + return s8Ret; +} + + +sint8 m2m_crypto_sha256_hash_finish(tstrM2mSha256Ctxt *pstrSha256Ctxt, uint8 *pu8Sha256Digest) +{ + sint8 s8Ret = M2M_ERR_FAIL; + tstrSHA256HashCtxt *pstrSHA256 = (tstrSHA256HashCtxt*)pstrSha256Ctxt; + if(pstrSHA256 != NULL) + { + uint32 u32ReadAddr; + uint32 u32WriteAddr = SHARED_MEM_BASE; + uint32 u32Addr = u32WriteAddr; + uint16 u16Offset; + uint16 u16PaddingLength; + uint16 u16NBlocks = 1; + uint32 u32RegVal = 0; + uint32 u32Idx,u32ByteIdx; + uint32 au32Digest[M2M_SHA256_DIGEST_LEN / 4]; + uint8 u8IsDone = 0; + + nm_write_reg(SHA256_CTRL,u32RegVal); + u32RegVal |= SHA256_CTRL_FORCE_SHA256_QUIT_MASK; + nm_write_reg(SHA256_CTRL,u32RegVal); + + if(pstrSHA256->u8InitHashFlag) + { + pstrSHA256->u8InitHashFlag = 0; + u32RegVal |= SHA256_CTRL_INIT_SHA256_STATE_MASK; + } + + /* Calculate the offset of the last data byte in the current block. */ + u16Offset = (uint16)(pstrSHA256->u32TotalLength % SHA_BLOCK_SIZE); + + /* Add the padding byte 0x80. */ + pstrSHA256->au8CurrentBlock[u16Offset ++] = 0x80; + + /* Calculate the required padding to complete + one Hash Block Size. + */ + u16PaddingLength = SHA_BLOCK_SIZE - u16Offset; + m2m_memset(&pstrSHA256->au8CurrentBlock[u16Offset], 0, u16PaddingLength); + + /* If the padding count is not enough to hold 64-bit representation of + the total input message length, one padding block is required. + */ + if(u16PaddingLength < 8) + { + nm_write_block(u32Addr, pstrSHA256->au8CurrentBlock, SHA_BLOCK_SIZE); + u32Addr += SHA_BLOCK_SIZE; + m2m_memset(pstrSHA256->au8CurrentBlock, 0, SHA_BLOCK_SIZE); + u16NBlocks ++; + } + + /* pack the length at the end of the padding block */ + PUTU32(pstrSHA256->u32TotalLength << 3, pstrSHA256->au8CurrentBlock, (SHA_BLOCK_SIZE - 4)); + + u32ReadAddr = u32WriteAddr + (u16NBlocks * SHA_BLOCK_SIZE); + nm_write_block(u32Addr, pstrSHA256->au8CurrentBlock, SHA_BLOCK_SIZE); + nm_write_reg(SHA256_DATA_LENGTH, (u16NBlocks * SHA_BLOCK_SIZE)); + nm_write_reg(SHA256_START_RD_ADDR, u32WriteAddr); + nm_write_reg(SHA256_START_WR_ADDR, u32ReadAddr); + + u32RegVal |= SHA256_CTRL_START_CALC_MASK; + u32RegVal |= SHA256_CTRL_WR_BACK_HASH_VALUE_MASK; + u32RegVal &= ~(0x7UL << 8); + u32RegVal |= (0x2UL << 8); + + nm_write_reg(SHA256_CTRL,u32RegVal); + + + /* 5. Wait for done_intr */ + while(!u8IsDone) + { + u32RegVal = nm_read_reg(SHA256_DONE_INTR_STS); + u8IsDone = u32RegVal & NBIT0; + } + nm_read_block(u32ReadAddr, (uint8*)au32Digest, 32); + + /* Convert the output words to an array of bytes. + */ + u32ByteIdx = 0; + for(u32Idx = 0; u32Idx < (M2M_SHA256_DIGEST_LEN / 4); u32Idx ++) + { + pu8Sha256Digest[u32ByteIdx ++] = BYTE_3(au32Digest[u32Idx]); + pu8Sha256Digest[u32ByteIdx ++] = BYTE_2(au32Digest[u32Idx]); + pu8Sha256Digest[u32ByteIdx ++] = BYTE_1(au32Digest[u32Idx]); + pu8Sha256Digest[u32ByteIdx ++] = BYTE_0(au32Digest[u32Idx]); + } + s8Ret = M2M_SUCCESS; + } + return s8Ret; +} + + +/*======*======*======*======*======*=======* +* RSA IMPLEMENTATION * +*======*======*======*======*======*========*/ + +static void FlipBuffer(uint8 *pu8InBuffer, uint8 *pu8OutBuffer, uint16 u16BufferSize) +{ + uint16 u16Idx; + for(u16Idx = 0; u16Idx < u16BufferSize; u16Idx ++) + { +#if ENABLE_FLIPPING == 1 + pu8OutBuffer[u16Idx] = pu8InBuffer[u16BufferSize - u16Idx - 1]; +#else + pu8OutBuffer[u16Idx] = pu8InBuffer[u16Idx]; +#endif + } +} + +void BigInt_ModExp +( + uint8 *pu8X, uint16 u16XSize, + uint8 *pu8E, uint16 u16ESize, + uint8 *pu8M, uint16 u16MSize, + uint8 *pu8R, uint16 u16RSize + ) +{ + uint32 u32Reg; + uint8 au8Tmp[780] = {0}; + uint32 u32XAddr = SHARED_MEM_BASE; + uint32 u32MAddr; + uint32 u32EAddr; + uint32 u32RAddr; + uint8 u8EMswBits = 32; + uint32 u32Mprime = 0x7F; + uint16 u16XSizeWords,u16ESizeWords; + uint32 u32Exponent; + + u16XSizeWords = (u16XSize + 3) / 4; + u16ESizeWords = (u16ESize + 3) / 4; + + u32MAddr = u32XAddr + (u16XSizeWords * 4); + u32EAddr = u32MAddr + (u16XSizeWords * 4); + u32RAddr = u32EAddr + (u16ESizeWords * 4); + + /* Reset the core. + */ + u32Reg = 0; + u32Reg |= BIGINT_MISC_CTRL_CTL_RESET; + u32Reg = nm_read_reg(BIGINT_MISC_CTRL); + u32Reg &= ~BIGINT_MISC_CTRL_CTL_RESET; + u32Reg = nm_read_reg(BIGINT_MISC_CTRL); + + nm_write_block(u32RAddr,au8Tmp, u16RSize); + + /* Write Input Operands to Chip Memory. + */ + /*------- X -------*/ + FlipBuffer(pu8X,au8Tmp,u16XSize); + nm_write_block(u32XAddr,au8Tmp,u16XSizeWords * 4); + + /*------- E -------*/ + m2m_memset(au8Tmp, 0, sizeof(au8Tmp)); + FlipBuffer(pu8E, au8Tmp, u16ESize); + nm_write_block(u32EAddr, au8Tmp, u16ESizeWords * 4); + u32Exponent = GET_UINT32(au8Tmp, (u16ESizeWords * 4) - 4); + while((u32Exponent & NBIT31)== 0) + { + u32Exponent <<= 1; + u8EMswBits --; + } + + /*------- M -------*/ + m2m_memset(au8Tmp, 0, sizeof(au8Tmp)); + FlipBuffer(pu8M, au8Tmp, u16XSize); + nm_write_block(u32MAddr, au8Tmp, u16XSizeWords * 4); + + /* Program the addresses of the input operands. + */ + nm_write_reg(BIGINT_ADDR_X, u32XAddr); + nm_write_reg(BIGINT_ADDR_E, u32EAddr); + nm_write_reg(BIGINT_ADDR_M, u32MAddr); + nm_write_reg(BIGINT_ADDR_R, u32RAddr); + + /* Mprime. + */ + nm_write_reg(BIGINT_M_PRIME,u32Mprime); + + /* Length. + */ + u32Reg = (u16XSizeWords & 0xFF); + u32Reg += ((u16ESizeWords & 0xFF) << 8); + u32Reg += (u8EMswBits << 16); + nm_write_reg(BIGINT_LENGTH,u32Reg); + + /* CTRL Register. + */ + u32Reg = nm_read_reg(BIGINT_MISC_CTRL); + u32Reg ^= BIGINT_MISC_CTRL_CTL_START; + u32Reg |= BIGINT_MISC_CTRL_CTL_FORCE_BARRETT; + //u32Reg |= BIGINT_MISC_CTRL_CTL_M_PRIME_VALID; +#if ENABLE_FLIPPING == 0 + u32Reg |= BIGINT_MISC_CTRL_CTL_MSW_FIRST; +#endif + nm_write_reg(BIGINT_MISC_CTRL,u32Reg); + + /* Wait for computation to complete. */ + while(1) + { + u32Reg = nm_read_reg(BIGINT_IRQ_STS); + if(u32Reg & BIGINT_IRQ_STS_DONE) + { + break; + } + } + nm_write_reg(BIGINT_IRQ_STS,0); + m2m_memset(au8Tmp, 0, sizeof(au8Tmp)); + nm_read_block(u32RAddr, au8Tmp, u16RSize); + FlipBuffer(au8Tmp, pu8R, u16RSize); +} + + + +#define MD5_DIGEST_SIZE (16) +#define SHA1_DIGEST_SIZE (20) + +static const uint8 au8TEncodingMD5[] = +{ + 0x30, 0x20, 0x30, 0x0C, 0x06, 0x08, 0x2A, 0x86, + 0x48, 0x86, 0xF7, 0x0D, 0x02, 0x05, 0x05, 0x00, + 0x04 +}; +/*!< Fixed part of the Encoding T for the MD5 hash algorithm. +*/ + + +static const uint8 au8TEncodingSHA1[] = +{ + 0x30, 0x21, 0x30, 0x09, 0x06, 0x05, 0x2B, 0x0E, + 0x03, 0x02, 0x1A, 0x05, 0x00, 0x04 +}; +/*!< Fixed part of the Encoding T for the SHA-1 hash algorithm. +*/ + + +static const uint8 au8TEncodingSHA2[] = +{ + 0x30, 0x31, 0x30, 0x0D, 0x06, 0x09, 0x60, 0x86, + 0x48, 0x01, 0x65, 0x03, 0x04, 0x02, 0x01, 0x05, + 0x00, 0x04 +}; +/*!< Fixed part of the Encoding T for the SHA-2 hash algorithm. +*/ + + +sint8 m2m_crypto_rsa_sign_verify(uint8 *pu8N, uint16 u16NSize, uint8 *pu8E, uint16 u16ESize, uint8 *pu8SignedMsgHash, + uint16 u16HashLength, uint8 *pu8RsaSignature) +{ + sint8 s8Ret = M2M_RSA_SIGN_FAIL; + + if((pu8N != NULL) && (pu8E != NULL) && (pu8RsaSignature != NULL) && (pu8SignedMsgHash != NULL)) + { + uint16 u16TLength, u16TEncodingLength; + uint8 *pu8T; + uint8 au8EM[512]; + + /* Selection of correct T Encoding based on the hash size. + */ + if(u16HashLength == MD5_DIGEST_SIZE) + { + pu8T = (uint8*)au8TEncodingMD5; + u16TEncodingLength = sizeof(au8TEncodingMD5); + } + else if(u16HashLength == SHA1_DIGEST_SIZE) + { + pu8T = (uint8*)au8TEncodingSHA1; + u16TEncodingLength = sizeof(au8TEncodingSHA1); + } + else + { + pu8T = (uint8*)au8TEncodingSHA2; + u16TEncodingLength = sizeof(au8TEncodingSHA2); + } + u16TLength = u16TEncodingLength + 1 + u16HashLength; + + /* If emLen < tLen + 11. + */ + if(u16NSize >= (u16TLength + 11)) + { + uint32 u32PSLength,u32Idx = 0; + + /* + RSA verification + */ + BigInt_ModExp(pu8RsaSignature, u16NSize, pu8E, u16ESize, pu8N, u16NSize, au8EM, u16NSize); + + u32PSLength = u16NSize - u16TLength - 3; + + /* + The calculated EM must match the following pattern. + *======*======*======*======*======* + * 0x00 || 0x01 || PS || 0x00 || T * + *======*======*======*======*======* + Where PS is all 0xFF + T is defined based on the hash algorithm. + */ + if((au8EM[0] == 0x00) && (au8EM[1] == 0x01)) + { + for(u32Idx = 2; au8EM[u32Idx] == 0xFF; u32Idx ++); + if(u32Idx == (u32PSLength + 2)) + { + if(au8EM[u32Idx ++] == 0x00) + { + if(!m2m_memcmp(&au8EM[u32Idx], pu8T, u16TEncodingLength)) + { + u32Idx += u16TEncodingLength; + if(au8EM[u32Idx ++] == u16HashLength) + s8Ret = m2m_memcmp(&au8EM[u32Idx], pu8SignedMsgHash, u16HashLength); + } + } + } + } + } + } + return s8Ret; +} + + +sint8 m2m_crypto_rsa_sign_gen(uint8 *pu8N, uint16 u16NSize, uint8 *pu8d, uint16 u16dSize, uint8 *pu8SignedMsgHash, + uint16 u16HashLength, uint8 *pu8RsaSignature) +{ + sint8 s8Ret = M2M_RSA_SIGN_FAIL; + + if((pu8N != NULL) && (pu8d != NULL) && (pu8RsaSignature != NULL) && (pu8SignedMsgHash != NULL)) + { + uint16 u16TLength, u16TEncodingLength; + uint8 *pu8T; + uint8 au8EM[512]; + + /* Selection of correct T Encoding based on the hash size. + */ + if(u16HashLength == MD5_DIGEST_SIZE) + { + pu8T = (uint8*)au8TEncodingMD5; + u16TEncodingLength = sizeof(au8TEncodingMD5); + } + else if(u16HashLength == SHA1_DIGEST_SIZE) + { + pu8T = (uint8*)au8TEncodingSHA1; + u16TEncodingLength = sizeof(au8TEncodingSHA1); + } + else + { + pu8T = (uint8*)au8TEncodingSHA2; + u16TEncodingLength = sizeof(au8TEncodingSHA2); + } + u16TLength = u16TEncodingLength + 1 + u16HashLength; + + /* If emLen < tLen + 11. + */ + if(u16NSize >= (u16TLength + 11)) + { + uint16 u16PSLength = 0; + uint16 u16Offset = 0; + + /* + The calculated EM must match the following pattern. + *======*======*======*======*======* + * 0x00 || 0x01 || PS || 0x00 || T * + *======*======*======*======*======* + Where PS is all 0xFF + T is defined based on the hash algorithm. + */ + au8EM[u16Offset ++] = 0; + au8EM[u16Offset ++] = 1; + u16PSLength = u16NSize - u16TLength - 3; + m2m_memset(&au8EM[u16Offset], 0xFF, u16PSLength); + u16Offset += u16PSLength; + au8EM[u16Offset ++] = 0; + m2m_memcpy(&au8EM[u16Offset], pu8T, u16TEncodingLength); + u16Offset += u16TEncodingLength; + au8EM[u16Offset ++] = u16HashLength; + m2m_memcpy(&au8EM[u16Offset], pu8SignedMsgHash, u16HashLength); + + /* + RSA Signature Generation + */ + BigInt_ModExp(au8EM, u16NSize, pu8d, u16dSize, pu8N, u16NSize, pu8RsaSignature, u16NSize); + s8Ret = M2M_RSA_SIGN_OK; + } + } + return s8Ret; +} + +#endif /* CONF_CRYPTO */ + +#ifdef CONF_CRYPTO_SOFT + +typedef struct { + tpfAppCryproCb pfAppCryptoCb; + uint8 * pu8Digest; + uint8 * pu8Rsa; + uint8 u8CryptoBusy; +}tstrCryptoCtxt; + +typedef struct { + uint8 au8N[M2M_MAX_RSA_LEN]; + uint8 au8E[M2M_MAX_RSA_LEN]; + uint8 au8Hash[M2M_SHA256_DIGEST_LEN]; + uint16 u16Nsz; + uint16 u16Esz; + uint16 u16Hsz; + uint8 _pad16_[2]; +}tstrRsaPayload; + +static tstrCryptoCtxt gstrCryptoCtxt; + + +/** +* @fn m2m_crypto_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr) +* @brief WiFi call back function +* @param [in] u8OpCode +* HIF Opcode type. +* @param [in] u16DataSize +* HIF data length. +* @param [in] u32Addr +* HIF address. +* @author +* @date +* @version 1.0 +*/ +static void m2m_crypto_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr) +{ + sint8 ret = M2M_SUCCESS; + gstrCryptoCtxt.u8CryptoBusy = 0; + if(u8OpCode == M2M_CRYPTO_RESP_SHA256_INIT) + { + tstrM2mSha256Ctxt strCtxt; + if (hif_receive(u32Addr, (uint8*) &strCtxt,sizeof(tstrM2mSha256Ctxt), 0) == M2M_SUCCESS) + { + tstrCyptoResp strResp; + if(hif_receive(u32Addr + sizeof(tstrM2mSha256Ctxt), (uint8*) &strResp,sizeof(tstrCyptoResp), 1) == M2M_SUCCESS) + { + if (gstrCryptoCtxt.pfAppCryptoCb) + gstrCryptoCtxt.pfAppCryptoCb(u8OpCode,&strResp,&strCtxt); + } + } + } + else if(u8OpCode == M2M_CRYPTO_RESP_SHA256_UPDATE) + { + tstrM2mSha256Ctxt strCtxt; + if (hif_receive(u32Addr, (uint8*) &strCtxt,sizeof(tstrM2mSha256Ctxt), 0) == M2M_SUCCESS) + { + tstrCyptoResp strResp; + if (hif_receive(u32Addr + sizeof(tstrM2mSha256Ctxt), (uint8*) &strResp,sizeof(tstrCyptoResp), 1) == M2M_SUCCESS) + { + if (gstrCryptoCtxt.pfAppCryptoCb) + gstrCryptoCtxt.pfAppCryptoCb(u8OpCode,&strResp,&strCtxt); + } + } + + } + else if(u8OpCode == M2M_CRYPTO_RESP_SHA256_FINSIH) + { + tstrCyptoResp strResp; + if (hif_receive(u32Addr + sizeof(tstrM2mSha256Ctxt), (uint8*) &strResp,sizeof(tstrCyptoResp), 0) == M2M_SUCCESS) + { + if (hif_receive(u32Addr + sizeof(tstrM2mSha256Ctxt) + sizeof(tstrCyptoResp), (uint8*)gstrCryptoCtxt.pu8Digest,M2M_SHA256_DIGEST_LEN, 1) == M2M_SUCCESS) + { + if (gstrCryptoCtxt.pfAppCryptoCb) + gstrCryptoCtxt.pfAppCryptoCb(u8OpCode,&strResp,gstrCryptoCtxt.pu8Digest); + + } + } + } + else if(u8OpCode == M2M_CRYPTO_RESP_RSA_SIGN_GEN) + { + tstrCyptoResp strResp; + if (hif_receive(u32Addr + sizeof(tstrRsaPayload), (uint8*)&strResp,sizeof(tstrCyptoResp), 0) == M2M_SUCCESS) + { + if (hif_receive(u32Addr + sizeof(tstrRsaPayload) + sizeof(tstrCyptoResp), (uint8*)gstrCryptoCtxt.pu8Rsa,M2M_MAX_RSA_LEN, 0) == M2M_SUCCESS) + { + if (gstrCryptoCtxt.pfAppCryptoCb) + gstrCryptoCtxt.pfAppCryptoCb(u8OpCode,&strResp,gstrCryptoCtxt.pu8Rsa); + } + } + } + else if(u8OpCode == M2M_CRYPTO_RESP_RSA_SIGN_VERIFY) + { + tstrCyptoResp strResp; + if (hif_receive(u32Addr + sizeof(tstrRsaPayload), (uint8*)&strResp,sizeof(tstrCyptoResp), 1) == M2M_SUCCESS) + { + if (gstrCryptoCtxt.pfAppCryptoCb) + gstrCryptoCtxt.pfAppCryptoCb(u8OpCode,&strResp,NULL); + } + } + else + { + M2M_ERR("u8Code %d ??\n",u8OpCode); + } + +} +/*! +@fn \ + sint8 m2m_crypto_init(); + +@brief crypto initialization + +@param[in] pfAppCryproCb + +*/ +sint8 m2m_crypto_init(tpfAppCryproCb pfAppCryproCb) +{ + sint8 ret = M2M_ERR_FAIL; + m2m_memset((uint8*)&gstrCryptoCtxt,0,sizeof(tstrCryptoCtxt)); + if(pfAppCryproCb != NULL) + { + gstrCryptoCtxt.pfAppCryptoCb = pfAppCryproCb; + ret = hif_register_cb(M2M_REQ_GROUP_CRYPTO,m2m_crypto_cb); + } + return ret; +} +/*! +@fn \ + sint8 m2m_sha256_hash_init(tstrM2mSha256Ctxt *psha256Ctxt); + +@brief SHA256 hash initialization + +@param[in] psha256Ctxt + Pointer to a sha256 context allocated by the caller. +*/ +sint8 m2m_crypto_sha256_hash_init(tstrM2mSha256Ctxt *psha256Ctxt) +{ + sint8 ret = M2M_ERR_FAIL; + if((psha256Ctxt != NULL)&&(!gstrCryptoCtxt.u8CryptoBusy)) + { + ret = hif_send(M2M_REQ_GROUP_CRYPTO,M2M_CRYPTO_REQ_SHA256_INIT|M2M_REQ_DATA_PKT,(uint8*)psha256Ctxt,sizeof(tstrM2mSha256Ctxt),NULL,0,0); + } + return ret; +} + + +/*! +@fn \ + sint8 m2m_sha256_hash_update(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Data, uint16 u16DataLength); + +@brief SHA256 hash update + +@param [in] psha256Ctxt + Pointer to the sha256 context. + +@param [in] pu8Data + Buffer holding the data submitted to the hash. + +@param [in] u16DataLength + Size of the data bufefr in bytes. +*/ +sint8 m2m_crypto_sha256_hash_update(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Data, uint16 u16DataLength) +{ + sint8 ret = M2M_ERR_FAIL; + if((!gstrCryptoCtxt.u8CryptoBusy) && (psha256Ctxt != NULL) && (pu8Data != NULL) && (u16DataLength < M2M_SHA256_MAX_DATA)) + { + ret = hif_send(M2M_REQ_GROUP_CRYPTO,M2M_CRYPTO_REQ_SHA256_UPDATE|M2M_REQ_DATA_PKT,(uint8*)psha256Ctxt,sizeof(tstrM2mSha256Ctxt),pu8Data,u16DataLength,sizeof(tstrM2mSha256Ctxt) + sizeof(tstrCyptoResp)); + } + return ret; + +} + + +/*! +@fn \ + sint8 m2m_sha256_hash_finish(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Sha256Digest); + +@brief SHA256 hash finalization + +@param[in] psha256Ctxt + Pointer to a sha256 context allocated by the caller. + +@param [in] pu8Sha256Digest + Buffer allocated by the caller which will hold the resultant SHA256 Digest. It must be allocated no less than M2M_SHA256_DIGEST_LEN. +*/ +sint8 m2m_crypto_sha256_hash_finish(tstrM2mSha256Ctxt *psha256Ctxt, uint8 *pu8Sha256Digest) +{ + sint8 ret = M2M_ERR_FAIL; + if((!gstrCryptoCtxt.u8CryptoBusy) && (psha256Ctxt != NULL) && (pu8Sha256Digest != NULL)) + { + gstrCryptoCtxt.pu8Digest = pu8Sha256Digest; + ret = hif_send(M2M_REQ_GROUP_CRYPTO,M2M_CRYPTO_REQ_SHA256_FINSIH|M2M_REQ_DATA_PKT,(uint8*)psha256Ctxt,sizeof(tstrM2mSha256Ctxt),NULL,0,0); + } + return ret; +} + + + + +/*! +@fn \ + sint8 m2m_rsa_sign_verify(uint8 *pu8N, uint16 u16NSize, uint8 *pu8E, uint16 u16ESize, uint8 *pu8SignedMsgHash, \ + uint16 u16HashLength, uint8 *pu8RsaSignature); + +@brief RSA Signature Verification + + The function shall request the RSA Signature verification from the WINC Firmware for the given message. The signed message shall be + compressed to the corresponding hash algorithm before calling this function. + The hash type is identified by the given hash length. For example, if the hash length is 32 bytes, then it is SHA256. + +@param[in] pu8N + RSA Key modulus n. + +@param[in] u16NSize + Size of the RSA modulus n in bytes. + +@param[in] pu8E + RSA public exponent. + +@param[in] u16ESize + Size of the RSA public exponent in bytes. + +@param[in] pu8SignedMsgHash + The hash digest of the signed message. + +@param[in] u16HashLength + The length of the hash digest. + +@param[out] pu8RsaSignature + Signature value to be verified. +*/ + + +sint8 m2m_crypto_rsa_sign_verify(uint8 *pu8N, uint16 u16NSize, uint8 *pu8E, uint16 u16ESize, uint8 *pu8SignedMsgHash, + uint16 u16HashLength, uint8 *pu8RsaSignature) +{ + sint8 ret = M2M_ERR_FAIL; + if((!gstrCryptoCtxt.u8CryptoBusy) && (pu8N != NULL) && (pu8E != NULL) && (pu8RsaSignature != NULL) && (pu8SignedMsgHash != NULL) + && (u16NSize != 0) && (u16ESize != 0) && (u16HashLength != 0) && (pu8RsaSignature != NULL) ) + + { + tstrRsaPayload strRsa = {0}; + + m2m_memcpy(strRsa.au8N,pu8N,u16NSize); + m2m_memcpy(strRsa.au8E,pu8E,u16ESize); + m2m_memcpy(strRsa.au8Hash,pu8SignedMsgHash,u16HashLength); + + strRsa.u16Esz = u16ESize; + strRsa.u16Hsz = u16HashLength; + strRsa.u16Nsz = u16NSize; + + ret = hif_send(M2M_REQ_GROUP_CRYPTO,M2M_CRYPTO_REQ_RSA_SIGN_VERIFY|M2M_REQ_DATA_PKT,(uint8*)&strRsa,sizeof(tstrRsaPayload),NULL,0,0); + + } + return ret; +} + + +/*! +@fn \ + sint8 m2m_rsa_sign_gen(uint8 *pu8N, uint16 u16NSize, uint8 *pu8d, uint16 u16dSize, uint8 *pu8SignedMsgHash, \ + uint16 u16HashLength, uint8 *pu8RsaSignature); + +@brief RSA Signature Generation + + The function shall request the RSA Signature generation from the WINC Firmware for the given message. The signed message shall be + compressed to the corresponding hash algorithm before calling this function. + The hash type is identified by the given hash length. For example, if the hash length is 32 bytes, then it is SHA256. + +@param[in] pu8N + RSA Key modulus n. + +@param[in] u16NSize + Size of the RSA modulus n in bytes. + +@param[in] pu8d + RSA private exponent. + +@param[in] u16dSize + Size of the RSA private exponent in bytes. + +@param[in] pu8SignedMsgHash + The hash digest of the signed message. + +@param[in] u16HashLength + The length of the hash digest. + +@param[out] pu8RsaSignature + Pointer to a user buffer allocated by teh caller shall hold the generated signature. +*/ +sint8 m2m_crypto_rsa_sign_gen(uint8 *pu8N, uint16 u16NSize, uint8 *pu8d, uint16 u16dSize, uint8 *pu8SignedMsgHash, + uint16 u16HashLength, uint8 *pu8RsaSignature) +{ + sint8 ret = M2M_ERR_FAIL; + if((!gstrCryptoCtxt.u8CryptoBusy) && (pu8N != NULL) && (pu8d != NULL) && (pu8RsaSignature != NULL) && (pu8SignedMsgHash != NULL) + && (u16NSize != 0) && (u16dSize != 0) && (u16HashLength != 0) && (pu8RsaSignature != NULL)) + + { + tstrRsaPayload strRsa = {0}; + + m2m_memcpy(strRsa.au8N,pu8N,u16NSize); + m2m_memcpy(strRsa.au8E,pu8d,u16dSize); + m2m_memcpy(strRsa.au8Hash,pu8SignedMsgHash,u16HashLength); + + strRsa.u16Esz = u16dSize; + strRsa.u16Hsz = u16HashLength; + strRsa.u16Nsz = u16NSize; + + gstrCryptoCtxt.pu8Rsa = pu8RsaSignature; + ret = hif_send(M2M_REQ_GROUP_CRYPTO,M2M_CRYPTO_REQ_RSA_SIGN_GEN|M2M_REQ_DATA_PKT,(uint8*)&strRsa,sizeof(tstrRsaPayload),NULL,0,0); + + } + return ret; +} + +#endif \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_hif.c b/ext/drivers/atmel/winc1500/driver/source/m2m_hif.c new file mode 100755 index 0000000000000..0f1cdd589ed00 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_hif.c @@ -0,0 +1,704 @@ +/** + * + * \file + * + * \brief This module contains M2M host interface APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "common/include/nm_common.h" +#include "driver/source/nmbus.h" +#include "bsp/include/nm_bsp.h" +#include "m2m_hif.h" +#include "driver/include/m2m_types.h" +#include "driver/source/nmasic.h" +#include "driver/include/m2m_periph.h" + +#if (defined NM_EDGE_INTERRUPT)&&(defined NM_LEVEL_INTERRUPT) +#error "only one type of interrupt NM_EDGE_INTERRUPT,NM_LEVEL_INTERRUPT" +#endif + +#if !((defined NM_EDGE_INTERRUPT)||(defined NM_LEVEL_INTERRUPT)) +#error "define interrupt type NM_EDGE_INTERRUPT,NM_LEVEL_INTERRUPT" +#endif + +#ifndef CORTUS_APP +#define NMI_AHB_DATA_MEM_BASE 0x30000 +#define NMI_AHB_SHARE_MEM_BASE 0xd0000 + +#define WIFI_HOST_RCV_CTRL_0 (0x1070) +#define WIFI_HOST_RCV_CTRL_1 (0x1084) +#define WIFI_HOST_RCV_CTRL_2 (0x1078) +#define WIFI_HOST_RCV_CTRL_3 (0x106c) +#define WAKE_VALUE (0x5678) +#define SLEEP_VALUE (0x4321) +#define WAKE_REG (0x1074) + + + +static volatile uint8 gu8ChipMode = 0; +static volatile uint8 gu8ChipSleep = 0; +static volatile uint8 gu8HifSizeDone = 0; +static volatile uint8 gu8Interrupt = 0; + +tpfHifCallBack pfWifiCb = NULL; /*!< pointer to Wi-Fi call back function */ +tpfHifCallBack pfIpCb = NULL; /*!< pointer to Socket call back function */ +tpfHifCallBack pfOtaCb = NULL; /*!< pointer to OTA call back function */ +tpfHifCallBack pfSigmaCb = NULL; +tpfHifCallBack pfHifCb = NULL; +tpfHifCallBack pfCryptoCb = NULL; + +static void isr(void) +{ + gu8Interrupt++; +#ifdef NM_LEVEL_INTERRUPT + nm_bsp_interrupt_ctrl(0); +#endif +} +static sint8 hif_set_rx_done(void) +{ + uint32 reg; + sint8 ret = M2M_SUCCESS; +#ifdef NM_EDGE_INTERRUPT + nm_bsp_interrupt_ctrl(1); +#endif + + ret = nm_read_reg_with_ret(WIFI_HOST_RCV_CTRL_0,®); + if(ret != M2M_SUCCESS)goto ERR1; + //reg &= ~(1<<0); + + /* Set RX Done */ + reg |= (1<<1); + ret = nm_write_reg(WIFI_HOST_RCV_CTRL_0,reg); + if(ret != M2M_SUCCESS)goto ERR1; +#ifdef NM_LEVEL_INTERRUPT + nm_bsp_interrupt_ctrl(1); +#endif +ERR1: + return ret; + +} +/** +* @fn static void m2m_hif_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr) +* @brief WiFi call back function +* @param [in] u8OpCode +* HIF Opcode type. +* @param [in] u16DataSize +* HIF data length. +* @param [in] u32Addr +* HIF address. +* @param [in] grp +* HIF group type. +* @author +* @date +* @version 1.0 +*/ +static void m2m_hif_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr) +{ + + +} +/** +* @fn NMI_API sint8 hif_chip_wake(void); +* @brief To Wakeup the chip. +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +sint8 hif_chip_wake(void) +{ + sint8 ret = M2M_SUCCESS; + if(gu8ChipSleep == 0) + { + if((gu8ChipMode == M2M_PS_DEEP_AUTOMATIC)||(gu8ChipMode == M2M_PS_MANUAL)) + { + ret = nm_clkless_wake(); + if(ret != M2M_SUCCESS)goto ERR1; + ret = nm_write_reg(WAKE_REG, WAKE_VALUE); + if(ret != M2M_SUCCESS)goto ERR1; + } + else + { + } + } + gu8ChipSleep++; +ERR1: + return ret; +} +/*! +@fn \ + NMI_API void hif_set_sleep_mode(uint8 u8Pstype); + +@brief + Set the sleep mode of the HIF layer. + +@param [in] u8Pstype + Sleep mode. + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ + +void hif_set_sleep_mode(uint8 u8Pstype) +{ + gu8ChipMode = u8Pstype; +} +/*! +@fn \ + NMI_API uint8 hif_get_sleep_mode(void); + +@brief + Get the sleep mode of the HIF layer. + +@return + The function SHALL return the sleep mode of the HIF layer. +*/ + +uint8 hif_get_sleep_mode(void) +{ + return gu8ChipMode; +} +/** +* @fn NMI_API sint8 hif_chip_sleep(void); +* @brief To make the chip sleep. +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +sint8 hif_chip_sleep(void) +{ + sint8 ret = M2M_SUCCESS; + + if(gu8ChipSleep >= 1) + { + gu8ChipSleep--; + } + + if(gu8ChipSleep == 0) + { + if((gu8ChipMode == M2M_PS_DEEP_AUTOMATIC)||(gu8ChipMode == M2M_PS_MANUAL)) + { + uint32 reg = 0; + ret = nm_write_reg(WAKE_REG, SLEEP_VALUE); + if(ret != M2M_SUCCESS)goto ERR1; + /* Clear bit 1 */ + ret = nm_read_reg_with_ret(0x1, ®); + if(ret != M2M_SUCCESS)goto ERR1; + if(reg&0x2) + { + reg &=~(1 << 1); + ret = nm_write_reg(0x1, reg); + } + } + else + { + } + } +ERR1: + return ret; +} +/** +* @fn NMI_API sint8 hif_init(void * arg); +* @brief To initialize HIF layer. +* @param [in] arg +* Pointer to the arguments. +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +sint8 hif_init(void * arg) +{ + pfWifiCb = NULL; + pfIpCb = NULL; + + gu8ChipSleep = 0; + gu8ChipMode = M2M_NO_PS; + + gu8Interrupt = 0; + nm_bsp_register_isr(isr); + + hif_register_cb(M2M_REQ_GROUP_HIF,m2m_hif_cb); + + return M2M_SUCCESS; +} +/** +* @fn NMI_API sint8 hif_deinit(void * arg); +* @brief To Deinitialize HIF layer. +* @param [in] arg +* Pointer to the arguments. +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ +sint8 hif_deinit(void * arg) +{ + sint8 ret = M2M_SUCCESS; +#if 0 + uint32 reg = 0, cnt=0; + while (reg != M2M_DISABLE_PS) + { + nm_bsp_sleep(1); + reg = nm_read_reg(STATE_REG); + if(++cnt > 1000) + { + M2M_DBG("failed to stop power save\n"); + break; + } + } +#endif + ret = hif_chip_wake(); + + gu8ChipMode = 0; + gu8ChipSleep = 0; + gu8HifSizeDone = 0; + gu8Interrupt = 0; + + pfWifiCb = NULL; + pfIpCb = NULL; + pfOtaCb = NULL; + pfHifCb = NULL; + + return ret; +} +/** +* @fn NMI_API sint8 hif_send(uint8 u8Gid,uint8 u8Opcode,uint8 *pu8CtrlBuf,uint16 u16CtrlBufSize, + uint8 *pu8DataBuf,uint16 u16DataSize, uint16 u16DataOffset) +* @brief Send packet using host interface. + +* @param [in] u8Gid +* Group ID. +* @param [in] u8Opcode +* Operation ID. +* @param [in] pu8CtrlBuf +* Pointer to the Control buffer. +* @param [in] u16CtrlBufSize + Control buffer size. +* @param [in] u16DataOffset + Packet Data offset. +* @param [in] pu8DataBuf +* Packet buffer Allocated by the caller. +* @param [in] u16DataSize + Packet buffer size (including the HIF header). +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +sint8 hif_send(uint8 u8Gid,uint8 u8Opcode,uint8 *pu8CtrlBuf,uint16 u16CtrlBufSize, + uint8 *pu8DataBuf,uint16 u16DataSize, uint16 u16DataOffset) +{ + sint8 ret = M2M_ERR_SEND; + volatile tstrHifHdr strHif; + + strHif.u8Opcode = u8Opcode&(~NBIT7); + strHif.u8Gid = u8Gid; + strHif.u16Length = M2M_HIF_HDR_OFFSET; + if(pu8DataBuf != NULL) + { + strHif.u16Length += u16DataOffset + u16DataSize; + } + else + { + strHif.u16Length += u16CtrlBufSize; + } + ret = hif_chip_wake(); + if(ret == M2M_SUCCESS) + { + volatile uint32 reg, dma_addr = 0; + volatile uint16 cnt = 0; + + reg = 0UL; + reg |= (uint32)u8Gid; + reg |= ((uint32)u8Opcode<<8); + reg |= ((uint32)strHif.u16Length<<16); + ret = nm_write_reg(NMI_STATE_REG,reg); + if(M2M_SUCCESS != ret) goto ERR1; + + + reg = 0; + reg |= (1<<1); + ret = nm_write_reg(WIFI_HOST_RCV_CTRL_2, reg); + if(M2M_SUCCESS != ret) goto ERR1; + dma_addr = 0; + + //nm_bsp_interrupt_ctrl(0); + + for(cnt = 0; cnt < 1000; cnt ++) + { + ret = nm_read_reg_with_ret(WIFI_HOST_RCV_CTRL_2,(uint32 *)®); + if(ret != M2M_SUCCESS) break; + if (!(reg & 0x2)) + { + ret = nm_read_reg_with_ret(0x150400,(uint32 *)&dma_addr); + if(ret != M2M_SUCCESS) { + /*in case of read error clear the dma address and return error*/ + dma_addr = 0; + } + /*in case of success break */ + break; + } + } + //nm_bsp_interrupt_ctrl(1); + + if (dma_addr != 0) + { + volatile uint32 u32CurrAddr; + u32CurrAddr = dma_addr; + strHif.u16Length=NM_BSP_B_L_16(strHif.u16Length); + ret = nm_write_block(u32CurrAddr, (uint8*)&strHif, M2M_HIF_HDR_OFFSET); + #ifdef CONF_WINC_USE_I2C + nm_bsp_sleep(1); + #endif + if(M2M_SUCCESS != ret) goto ERR1; + u32CurrAddr += M2M_HIF_HDR_OFFSET; + if(pu8CtrlBuf != NULL) + { + ret = nm_write_block(u32CurrAddr, pu8CtrlBuf, u16CtrlBufSize); + #ifdef CONF_WINC_USE_I2C + nm_bsp_sleep(1); + #endif + if(M2M_SUCCESS != ret) goto ERR1; + u32CurrAddr += u16CtrlBufSize; + } + if(pu8DataBuf != NULL) + { + u32CurrAddr += (u16DataOffset - u16CtrlBufSize); + ret = nm_write_block(u32CurrAddr, pu8DataBuf, u16DataSize); + #ifdef CONF_WINC_USE_I2C + nm_bsp_sleep(1); + #endif + if(M2M_SUCCESS != ret) goto ERR1; + u32CurrAddr += u16DataSize; + } + + reg = dma_addr << 2; + reg |= (1 << 1); + ret = nm_write_reg(WIFI_HOST_RCV_CTRL_3, reg); + if(M2M_SUCCESS != ret) goto ERR1; + } + else + { + M2M_DBG("Failed to alloc rx size\r"); + ret = M2M_ERR_MEM_ALLOC; + goto ERR1; + } + + } + else + { + M2M_ERR("(HIF)Fail to wakup the chip\n"); + goto ERR1; + } + ret = hif_chip_sleep(); + +ERR1: + return ret; +} +/** +* @fn hif_isr +* @brief Host interface interrupt service routine +* @author M. Abdelmawla +* @date 15 July 2012 +* @return 1 in case of interrupt received else 0 will be returned +* @version 1.0 +*/ +static sint8 hif_isr(void) +{ + sint8 ret = M2M_ERR_BUS_FAIL; + uint32 reg; + volatile tstrHifHdr strHif; + + ret = hif_chip_wake(); + if(ret == M2M_SUCCESS) + { + ret = nm_read_reg_with_ret(WIFI_HOST_RCV_CTRL_0, ®); + if(M2M_SUCCESS == ret) + { + if(reg & 0x1) /* New interrupt has been received */ + { + uint16 size; + + nm_bsp_interrupt_ctrl(0); + /*Clearing RX interrupt*/ + reg &= ~(1<<0); + ret = nm_write_reg(WIFI_HOST_RCV_CTRL_0,reg); + if(ret != M2M_SUCCESS)goto ERR1; + gu8HifSizeDone = 0; + size = (uint16)((reg >> 2) & 0xfff); + if (size > 0) { + uint32 address = 0; + /** + start bus transfer + **/ + ret = nm_read_reg_with_ret(WIFI_HOST_RCV_CTRL_1, &address); + if(M2M_SUCCESS != ret) + { + M2M_ERR("(hif) WIFI_HOST_RCV_CTRL_1 bus fail\n"); + nm_bsp_interrupt_ctrl(1); + goto ERR1; + } + ret = nm_read_block(address, (uint8*)&strHif, sizeof(tstrHifHdr)); + strHif.u16Length = NM_BSP_B_L_16(strHif.u16Length); + if(M2M_SUCCESS != ret) + { + M2M_ERR("(hif) address bus fail\n"); + nm_bsp_interrupt_ctrl(1); + goto ERR1; + } + if(strHif.u16Length != size) + { + if((size - strHif.u16Length) > 4) + { + M2M_ERR("(hif) Corrupted packet Size = %u \n", + size, strHif.u16Length, strHif.u8Gid, strHif.u8Opcode); + nm_bsp_interrupt_ctrl(1); + ret = M2M_ERR_BUS_FAIL; + goto ERR1; + } + } + + if(M2M_REQ_GROUP_WIFI == strHif.u8Gid) + { + if(pfWifiCb) + pfWifiCb(strHif.u8Opcode,strHif.u16Length - M2M_HIF_HDR_OFFSET, address + M2M_HIF_HDR_OFFSET); + + } + else if(M2M_REQ_GROUP_IP == strHif.u8Gid) + { + if(pfIpCb) + pfIpCb(strHif.u8Opcode,strHif.u16Length - M2M_HIF_HDR_OFFSET, address + M2M_HIF_HDR_OFFSET); + } + else if(M2M_REQ_GROUP_OTA == strHif.u8Gid) + { + if(pfOtaCb) + pfOtaCb(strHif.u8Opcode,strHif.u16Length - M2M_HIF_HDR_OFFSET, address + M2M_HIF_HDR_OFFSET); + } + else if(M2M_REQ_GROUP_CRYPTO == strHif.u8Gid) + { + if(pfCryptoCb) + pfCryptoCb(strHif.u8Opcode,strHif.u16Length - M2M_HIF_HDR_OFFSET, address + M2M_HIF_HDR_OFFSET); + } + else if(M2M_REQ_GROUP_SIGMA == strHif.u8Gid) + { + if(pfSigmaCb) + pfSigmaCb(strHif.u8Opcode,strHif.u16Length - M2M_HIF_HDR_OFFSET, address + M2M_HIF_HDR_OFFSET); + } + else + { + M2M_ERR("(hif) invalid group ID\n"); + ret = M2M_ERR_BUS_FAIL; + goto ERR1; + } + #ifndef ENABLE_UNO_BOARD + if(!gu8HifSizeDone) + { + M2M_ERR("(hif) host app didn't set RX Done\n"); + ret = hif_set_rx_done(); + } + #endif + } + else + { + ret = M2M_ERR_RCV; + M2M_ERR("(hif) Wrong Size\n"); + goto ERR1; + } + } + else + { +#ifndef WIN32 + M2M_ERR("(hif) False interrupt %lx",reg); +#endif + } + } + else + { + M2M_ERR("(hif) Fail to Read interrupt reg\n"); + goto ERR1; + } + } + else + { + M2M_ERR("(hif) FAIL to wakeup the chip\n"); + goto ERR1; + } + + ret = hif_chip_sleep(); +ERR1: + return ret; +} + +/** +* @fn hif_handle_isr(void) +* @brief Handle interrupt received from NMC1500 firmware. +* @return The function SHALL return 0 for success and a negative value otherwise. +*/ + +sint8 hif_handle_isr(void) +{ + sint8 ret = M2M_SUCCESS; + + while (gu8Interrupt) { + /*must be at that place because of the race of interrupt increment and that decrement*/ + /*when the interrupt enabled*/ + gu8Interrupt--; + while(1) + { + ret = hif_isr(); + if(ret == M2M_SUCCESS) { + /*we will try forever untill we get that interrupt*/ + /*Fail return errors here due to bus errors (reading expected values)*/ + break; + } else { + M2M_ERR("(HIF) Fail to handle interrupt %d try Again..\n",ret); + } + } + } + + return ret; +} +/* +* @fn hif_receive +* @brief Host interface interrupt serviece routine +* @param [in] u32Addr +* Receive start address +* @param [out] pu8Buf +* Pointer to receive buffer. Allocated by the caller +* @param [in] u16Sz +* Receive buffer size +* @param [in] isDone +* If you don't need any more packets send True otherwise send false +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ +sint8 hif_receive(uint32 u32Addr, uint8 *pu8Buf, uint16 u16Sz, uint8 isDone) +{ + uint32 address, reg; + uint16 size; + sint8 ret = M2M_SUCCESS; + + if(u32Addr == 0 ||pu8Buf == NULL || u16Sz == 0) + { + if(isDone) + { + gu8HifSizeDone = 1; + + /* set RX done */ + ret = hif_set_rx_done(); + } + else + { + ret = M2M_ERR_FAIL; + M2M_ERR(" hif_receive: Invalid argument\n"); + } + goto ERR1; + } + + ret = nm_read_reg_with_ret(WIFI_HOST_RCV_CTRL_0,®); + if(ret != M2M_SUCCESS)goto ERR1; + + + size = (uint16)((reg >> 2) & 0xfff); + ret = nm_read_reg_with_ret(WIFI_HOST_RCV_CTRL_1,&address); + if(ret != M2M_SUCCESS)goto ERR1; + + + if(u16Sz > size) + { + ret = M2M_ERR_FAIL; + M2M_ERR("APP Requested Size is larger than the recived buffer size <%d><%d>\n",u16Sz, size); + goto ERR1; + } + if((u32Addr < address)||((u32Addr + u16Sz)>(address+size))) + { + ret = M2M_ERR_FAIL; + M2M_ERR("APP Requested Address beyond the recived buffer address and length\n"); + goto ERR1; + } + + /* Receive the payload */ + ret = nm_read_block(u32Addr, pu8Buf, u16Sz); + if(ret != M2M_SUCCESS)goto ERR1; + + /* check if this is the last packet */ + if((((address + size) - (u32Addr + u16Sz)) <= 0) || isDone) + { + gu8HifSizeDone = 1; + + /* set RX done */ + ret = hif_set_rx_done(); + } + + + +ERR1: + return ret; +} + +/** +* @fn hif_register_cb +* @brief To set Callback function for every compantent Component +* @param [in] u8Grp +* Group to which the Callback function should be set. +* @param [in] fn +* function to be set +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +sint8 hif_register_cb(uint8 u8Grp,tpfHifCallBack fn) +{ + sint8 ret = M2M_SUCCESS; + switch(u8Grp) + { + case M2M_REQ_GROUP_IP: + pfIpCb = fn; + break; + case M2M_REQ_GROUP_WIFI: + pfWifiCb = fn; + break; + case M2M_REQ_GROUP_OTA: + pfOtaCb = fn; + break; + case M2M_REQ_GROUP_HIF: + pfHifCb = fn; + break; + case M2M_REQ_GROUP_CRYPTO: + pfCryptoCb = fn; + break; + case M2M_REQ_GROUP_SIGMA: + pfSigmaCb = fn; + break; + default: + M2M_ERR("GRp ? %d\n",u8Grp); + ret = M2M_ERR_FAIL; + break; + } + return ret; +} + +#endif diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_hif.h b/ext/drivers/atmel/winc1500/driver/source/m2m_hif.h new file mode 100755 index 0000000000000..1a6eee2e1ad91 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_hif.h @@ -0,0 +1,241 @@ +/** + * + * \file + * + * \brief This module contains M2M host interface APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _M2M_HIF_ +#define _M2M_HIF_ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "common/include/nm_common.h" +/*!< Include depends on UNO Board is used or not*/ +#ifdef ENABLE_UNO_BOARD +#include "m2m_uno_hif.h" +#endif + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#define M2M_HIF_MAX_PACKET_SIZE (1600 - 4) +/*!< Maximum size of the buffer could be transferred between Host and Firmware. +*/ + +#define M2M_HIF_HDR_OFFSET (sizeof(tstrHifHdr) + 4) + +/** +* @struct tstrHifHdr +* @brief Structure to hold HIF header +*/ +typedef struct +{ + uint8 u8Gid; /*!< Group ID */ + uint8 u8Opcode; /*!< OP code */ + uint16 u16Length; /*!< Payload length */ +}tstrHifHdr; + +#ifdef __cplusplus + extern "C" { +#endif + +/*! +@typedef typedef void (*tpfHifCallBack)(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr); +@brief used to point to Wi-Fi call back function depend on Arduino project or other projects. +@param [in] u8OpCode + HIF Opcode type. +@param [in] u16DataSize + HIF data length. +@param [in] u32Addr + HIF address. +@param [in] grp + HIF group type. +*/ +typedef void (*tpfHifCallBack)(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr); +/** +* @fn NMI_API sint8 hif_init(void * arg); +* @brief + To initialize HIF layer. +* @param [in] arg +* Pointer to the arguments. +* @return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ +NMI_API sint8 hif_init(void * arg); +/** +* @fn NMI_API sint8 hif_deinit(void * arg); +* @brief + To Deinitialize HIF layer. +* @param [in] arg +* Pointer to the arguments. +* @return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ +NMI_API sint8 hif_deinit(void * arg); +/** +* @fn NMI_API sint8 hif_send(uint8 u8Gid,uint8 u8Opcode,uint8 *pu8CtrlBuf,uint16 u16CtrlBufSize, + uint8 *pu8DataBuf,uint16 u16DataSize, uint16 u16DataOffset) +* @brief Send packet using host interface. + +* @param [in] u8Gid +* Group ID. +* @param [in] u8Opcode +* Operation ID. +* @param [in] pu8CtrlBuf +* Pointer to the Control buffer. +* @param [in] u16CtrlBufSize + Control buffer size. +* @param [in] u16DataOffset + Packet Data offset. +* @param [in] pu8DataBuf +* Packet buffer Allocated by the caller. +* @param [in] u16DataSize + Packet buffer size (including the HIF header). +* @return The function shall return ZERO for successful operation and a negative value otherwise. +*/ +NMI_API sint8 hif_send(uint8 u8Gid,uint8 u8Opcode,uint8 *pu8CtrlBuf,uint16 u16CtrlBufSize, + uint8 *pu8DataBuf,uint16 u16DataSize, uint16 u16DataOffset); +/* +* @fn hif_receive +* @brief Host interface interrupt serviece routine +* @param [in] u32Addr +* Receive start address +* @param [out] pu8Buf +* Pointer to receive buffer. Allocated by the caller +* @param [in] u16Sz +* Receive buffer size +* @param [in] isDone +* If you don't need any more packets send True otherwise send false +* @return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +NMI_API sint8 hif_receive(uint32 u32Addr, uint8 *pu8Buf, uint16 u16Sz, uint8 isDone); +/** +* @fn hif_register_cb +* @brief + To set Callback function for every Component. + +* @param [in] u8Grp +* Group to which the Callback function should be set. + +* @param [in] fn +* function to be set to the specified group. +* @return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ +NMI_API sint8 hif_register_cb(uint8 u8Grp,tpfHifCallBack fn); +/** +* @fn NMI_API sint8 hif_chip_sleep(void); +* @brief + To make the chip sleep. +* @return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ +NMI_API sint8 hif_chip_sleep(void); +/** +* @fn NMI_API sint8 hif_chip_wake(void); +* @brief + To Wakeup the chip. +* @return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ + +NMI_API sint8 hif_chip_wake(void); +/*! +@fn \ + NMI_API void hif_set_sleep_mode(uint8 u8Pstype); + +@brief + Set the sleep mode of the HIF layer. + +@param [in] u8Pstype + Sleep mode. + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ + +NMI_API void hif_set_sleep_mode(uint8 u8Pstype); +/*! +@fn \ + NMI_API uint8 hif_get_sleep_mode(void); + +@brief + Get the sleep mode of the HIF layer. + +@return + The function SHALL return the sleep mode of the HIF layer. +*/ + +NMI_API uint8 hif_get_sleep_mode(void); + +#ifdef CORTUS_APP +/** +* @fn hif_Resp_handler(uint8 *pu8Buffer, uint16 u16BufferSize) +* @brief + Response handler for HIF layer. + +* @param [in] pu8Buffer + Pointer to the buffer. + +* @param [in] u16BufferSize + Buffer size. + +* @return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 hif_Resp_handler(uint8 *pu8Buffer, uint16 u16BufferSize); +#endif + +/** +* @fn hif_handle_isr(void) +* @brief + Handle interrupt received from NMC1500 firmware. +* @return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 hif_handle_isr(void); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_ota.c b/ext/drivers/atmel/winc1500/driver/source/m2m_ota.c new file mode 100755 index 0000000000000..096ff45f20391 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_ota.c @@ -0,0 +1,340 @@ +/** + * + * \file + * + * \brief NMC1500 IoT OTA Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#include "common/include/nm_common.h" +#include "driver/include/m2m_types.h" +#include "driver/include/m2m_ota.h" +#include "driver/source/m2m_hif.h" +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +static tpfOtaUpdateCb gpfOtaUpdateCb = NULL; +static tpfOtaNotifCb gpfOtaNotifCb = NULL; + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/** +* @fn m2m_wifi_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr, uint8 grp) +* @brief WiFi call back function +* @param [in] u8OpCode +* HIF Opcode type. +* @param [in] u16DataSize +* HIF data length. +* @param [in] u32Addr +* HIF address. +* @param [in] grp +* HIF group type. +* @author +* @date +* @version 1.0 +*/ +static void m2m_ota_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr) +{ + sint8 ret = M2M_SUCCESS; + if(u8OpCode == M2M_OTA_RESP_NOTIF_UPDATE_INFO) + { + tstrOtaUpdateInfo strOtaUpdateInfo; + m2m_memset((uint8*)&strOtaUpdateInfo,0,sizeof(tstrOtaUpdateInfo)); + ret = hif_receive(u32Addr,(uint8*)&strOtaUpdateInfo,sizeof(tstrOtaUpdateInfo),0); + if(ret == M2M_SUCCESS) + { + if(gpfOtaNotifCb) + gpfOtaNotifCb(&strOtaUpdateInfo); + } + } + else if (u8OpCode == M2M_OTA_RESP_UPDATE_STATUS) + { + tstrOtaUpdateStatusResp strOtaUpdateStatusResp; + m2m_memset((uint8*)&strOtaUpdateStatusResp,0,sizeof(tstrOtaUpdateStatusResp)); + ret = hif_receive(u32Addr, (uint8*) &strOtaUpdateStatusResp,sizeof(tstrOtaUpdateStatusResp), 0); + if(ret == M2M_SUCCESS) + { + if(gpfOtaUpdateCb) + gpfOtaUpdateCb(strOtaUpdateStatusResp.u8OtaUpdateStatusType,strOtaUpdateStatusResp.u8OtaUpdateStatus); + } + } + else + { + M2M_ERR("Invaild OTA resp %d ?\n",u8OpCode); + } + +} +/*! +@fn \ + NMI_API sint8 m2m_ota_init(tpfOtaUpdateCb pfOtaUpdateCb, tpfOtaNotifCb pfOtaNotifCb); + +@brief + Initialize the OTA layer. + +@param [in] pfOtaUpdateCb + OTA Update callback function + +@param [in] pfOtaNotifCb + OTA notify callback function + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_init(tpfOtaUpdateCb pfOtaUpdateCb, tpfOtaNotifCb pfOtaNotifCb) +{ + sint8 ret = M2M_SUCCESS; + + if(pfOtaUpdateCb){ + gpfOtaUpdateCb = pfOtaUpdateCb; + }else{ + M2M_ERR("Invaild Ota update cb\n"); + } + if(pfOtaNotifCb){ + gpfOtaNotifCb = pfOtaNotifCb; + }else{ + M2M_ERR("Invaild Ota notify cb\n"); + } + + hif_register_cb(M2M_REQ_GROUP_OTA,m2m_ota_cb); + + return ret; +} +/*! +@fn \ + NMI_API sint8 m2m_ota_notif_set_url(uint8 * u8Url); + +@brief + Set the OTA url + +@param [in] u8Url + The url server address + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_notif_set_url(uint8 * u8Url) +{ + sint8 ret = M2M_SUCCESS; + uint16 u16UrlSize = m2m_strlen(u8Url) + 1; + /*Todo: we may change it to data pkt but we need to give it higer priority + but the priorty is not implemnted yet in data pkt + */ + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_START_UPDATE,u8Url,u16UrlSize,NULL,0,0); + return ret; + +} + +/*! +@fn \ + NMI_API sint8 m2m_ota_notif_check_for_update(void); + +@brief + check for ota update + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_notif_check_for_update(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_NOTIF_CHECK_FOR_UPDATE,NULL,0,NULL,0,0); + return ret; +} + +/*! +@fn \ + NMI_API sint8 m2m_ota_notif_sched(uint32 u32Period); + +@brief + Schedule OTA update + +@param [in] u32Period + Period in days + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_notif_sched(uint32 u32Period) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_NOTIF_CHECK_FOR_UPDATE,NULL,0,NULL,0,0); + return ret; +} + +/*! +@fn \ + NMI_API sint8 m2m_ota_start_update(uint8 * u8DownloadUrl); + +@brief + Request OTA start update using the downloaded url + +@param [in] u8DownloadUrl + The download firmware url, you get it from device info + +@return + The function SHALL return 0 for success and a negative value otherwise. + +*/ +NMI_API sint8 m2m_ota_start_update(uint8 * u8DownloadUrl) +{ + sint8 ret = M2M_SUCCESS; + uint16 u16DurlSize = m2m_strlen(u8DownloadUrl) + 1; + /*Todo: we may change it to data pkt but we need to give it higer priority + but the priorty is not implemnted yet in data pkt + */ + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_START_UPDATE,u8DownloadUrl,u16DurlSize,NULL,0,0); + return ret; +} + + +/*! +@fn \ + NMI_API sint8 m2m_ota_rollback(void); + +@brief + Request OTA Rollback image + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_rollback(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_ROLLBACK,NULL,0,NULL,0,0); + return ret; +} + + +/*! +@fn \ + NMI_API sint8 m2m_ota_switch_firmware(void); + +@brief + Switch to the upgraded Firmware + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_switch_firmware(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_SWITCH_FIRMWARE,NULL,0,NULL,0,0); + return ret; +} +/*! +@fn \ + NMI_API sint8 m2m_ota_get_firmware_version(tstrM2mRev * pstrRev); + +@brief + Get the OTA Firmware version. + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_ota_get_firmware_version(tstrM2mRev * pstrRev) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_chip_wake(); + if(ret == M2M_SUCCESS) + { + ret = nm_get_ota_firmware_info(pstrRev); + hif_chip_sleep(); + } + return ret; +} +#if 0 +#define M2M_OTA_FILE "../../../m2m_ota.dat" +NMI_API sint8 m2m_ota_test(void) +{ + uint32 page = 0; + uint8 buffer[1500]; + uint32 u32Sz = 0; + sint8 ret = M2M_SUCCESS; + FILE *fp =NULL; + fp = fopen(M2M_OTA_FILE,"rb"); + if(fp) + { + fseek(fp, 0L, SEEK_END); + u32Sz = ftell(fp); + fseek(fp, 0L, SEEK_SET); + + while(u32Sz > 0) + { + { + page = (rand()%1400); + + if((page<100)||(page>1400)) page = 1400; + } + + if(u32Sz>page) + { + u32Sz-=page; + } + else + { + page = u32Sz; + u32Sz = 0; + } + printf("page %d\n", (int)page); + fread(buffer,page,1,fp); + ret = hif_send(M2M_REQ_GROUP_OTA,M2M_OTA_REQ_TEST|M2M_REQ_DATA_PKT,NULL,0,(uint8*)&buffer,page,0); + if(ret != M2M_SUCCESS) + { + M2M_ERR("\n"); + } + nm_bsp_sleep(1); + } + + } + else + { + M2M_ERR("nO err\n"); + } + return ret; +} +#endif + diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_periph.c b/ext/drivers/atmel/winc1500/driver/source/m2m_periph.c new file mode 100755 index 0000000000000..689254df10401 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_periph.c @@ -0,0 +1,158 @@ +/** + * + * \file + * + * \brief NMC1500 Peripherials Application Interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "driver/include/m2m_periph.h" +#include "driver/source/nmasic.h" +#include "m2m_hif.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +#define GPIO_OP_DIR 0 +#define GPIO_OP_SET 1 +#define GPIO_OP_GET 2 +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +STATIC FUNCTIONS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +static sint8 get_gpio_idx(uint8 u8GpioNum) +{ + if(u8GpioNum >= M2M_PERIPH_GPIO_MAX) return -1; + if(u8GpioNum == M2M_PERIPH_GPIO15) { return 15; + } else if(u8GpioNum == M2M_PERIPH_GPIO16) { return 16; + } else if(u8GpioNum == M2M_PERIPH_GPIO18) { return 18; + } else if(u8GpioNum == M2M_PERIPH_GPIO3) { return 3; + } else if(u8GpioNum == M2M_PERIPH_GPIO4) { return 4; + } else if(u8GpioNum == M2M_PERIPH_GPIO5) { return 5; + } else if(u8GpioNum == M2M_PERIPH_GPIO6) { return 6; + } else { + return -2; + } +} +/* + * GPIO read/write skeleton with wakeup/sleep capability. + */ +static sint8 gpio_ioctl(uint8 op, uint8 u8GpioNum, uint8 u8InVal, uint8 * pu8OutVal) +{ + sint8 ret, gpio; + + ret = hif_chip_wake(); + if(ret != M2M_SUCCESS) goto _EXIT; + + gpio = get_gpio_idx(u8GpioNum); + if(gpio < 0) goto _EXIT1; + + if(op == GPIO_OP_DIR) { + ret = set_gpio_dir((uint8)gpio, u8InVal); + } else if(op == GPIO_OP_SET) { + ret = set_gpio_val((uint8)gpio, u8InVal); + } else if(op == GPIO_OP_GET) { + ret = get_gpio_val((uint8)gpio, pu8OutVal); + } + if(ret != M2M_SUCCESS) goto _EXIT1; + +_EXIT1: + ret = hif_chip_sleep(); +_EXIT: + return ret; +} +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION IMPLEMENTATION +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +sint8 m2m_periph_init(tstrPerphInitParam * param) +{ + return M2M_SUCCESS; +} + +sint8 m2m_periph_gpio_set_dir(uint8 u8GpioNum, uint8 u8GpioDir) +{ + return gpio_ioctl(GPIO_OP_DIR, u8GpioNum, u8GpioDir, NULL); +} + +sint8 m2m_periph_gpio_set_val(uint8 u8GpioNum, uint8 u8GpioVal) +{ + return gpio_ioctl(GPIO_OP_SET, u8GpioNum, u8GpioVal, NULL); +} + +sint8 m2m_periph_gpio_get_val(uint8 u8GpioNum, uint8 * pu8GpioVal) +{ + return gpio_ioctl(GPIO_OP_GET, u8GpioNum, 0, pu8GpioVal); +} + +sint8 m2m_periph_gpio_pullup_ctrl(uint8 u8GpioNum, uint8 u8PullupEn) +{ + /* TBD */ + return M2M_SUCCESS; +} + +sint8 m2m_periph_i2c_master_init(tstrI2cMasterInitParam * param) +{ + /* TBD */ + return M2M_SUCCESS; +} + +sint8 m2m_periph_i2c_master_write(uint8 u8SlaveAddr, uint8 * pu8Buf, uint16 u16BufLen, uint8 flags) +{ + /* TBD */ + return M2M_SUCCESS; +} + +sint8 m2m_periph_i2c_master_read(uint8 u8SlaveAddr, uint8 * pu8Buf, uint16 u16BufLen, uint16 * pu16ReadLen, uint8 flags) +{ + /* TBD */ + return M2M_SUCCESS; +} + + +sint8 m2m_periph_pullup_ctrl(uint32 pinmask, uint8 enable) +{ + return pullup_ctrl(pinmask, enable); +} diff --git a/ext/drivers/atmel/winc1500/driver/source/m2m_wifi.c b/ext/drivers/atmel/winc1500/driver/source/m2m_wifi.c new file mode 100755 index 0000000000000..d087f024f4535 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/m2m_wifi.c @@ -0,0 +1,1322 @@ +/** + * + * \file + * + * \brief This module contains M2M Wi-Fi APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "driver/include/m2m_wifi.h" +#include "driver/source/m2m_hif.h" +#include "driver/source/nmasic.h" + +/** + * \defgroup winc1500_group WINC1500 (Wi-Fi) + * + * \{ + */ + +static volatile uint8 gu8ChNum; +static volatile uint8 gu8scanInProgress = 0; +static tpfAppWifiCb gpfAppWifiCb = NULL; + + +#ifdef ETH_MODE +static tpfAppEthCb gpfAppEthCb = NULL; +static uint8* gau8ethRcvBuf=NULL; +static uint16 gu16ethRcvBufSize ; +#endif + + +//#define CONF_MGMT +#ifdef CONF_MGMT +static tpfAppMonCb gpfAppMonCb = NULL; +static struct _tstrMgmtCtrl +{ + uint8* pu8Buf; + uint16 u16Offset; + uint16 u16Sz; +} +gstrMgmtCtrl = {NULL, 0 , 0}; +#endif +/** +* @fn m2m_wifi_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr, uint8 grp) +* @brief WiFi call back function +* @param [in] u8OpCode +* HIF Opcode type. +* @param [in] u16DataSize +* HIF data length. +* @param [in] u32Addr +* HIF address. +* @param [in] grp +* HIF group type. +* @author +* @date +* @version 1.0 +*/ +static void m2m_wifi_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr) +{ + uint8 rx_buf[8]; + if (u8OpCode == M2M_WIFI_RESP_CON_STATE_CHANGED) + { + tstrM2mWifiStateChanged strState; + if (hif_receive(u32Addr, (uint8*) &strState,sizeof(tstrM2mWifiStateChanged), 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_CON_STATE_CHANGED, &strState); + } + } + else if (u8OpCode == M2M_WIFI_RESP_GET_SYS_TIME) + { + tstrSystemTime strSysTime; + if (hif_receive(u32Addr, (uint8*) &strSysTime,sizeof(tstrSystemTime), 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_GET_SYS_TIME, &strSysTime); + } + } + else if(u8OpCode == M2M_WIFI_RESP_CONN_INFO) + { + tstrM2MConnInfo strConnInfo; + if(hif_receive(u32Addr, (uint8*)&strConnInfo, sizeof(tstrM2MConnInfo), 1) == M2M_SUCCESS) + { + if(gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_CONN_INFO, &strConnInfo); + } + } + else if (u8OpCode == M2M_WIFI_RESP_MEMORY_RECOVER) + { +#if 0 + if (hif_receive(u32Addr, rx_buf, 4, 1) == M2M_SUCCESS) + { + tstrM2mWifiStateChanged strState; + m2m_memcpy((uint8*) &strState, rx_buf,sizeof(tstrM2mWifiStateChanged)); + if (app_wifi_recover_cb) + app_wifi_recover_cb(strState.u8CurrState); + } +#endif + } + else if (u8OpCode == M2M_WIFI_REQ_DHCP_CONF) + { + tstrM2MIPConfig strIpConfig; + if (hif_receive(u32Addr, (uint8 *)&strIpConfig, sizeof(tstrM2MIPConfig), 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_REQ_DHCP_CONF, (uint8 *)&strIpConfig); + } + } + else if (u8OpCode == M2M_WIFI_REQ_WPS) + { + tstrM2MWPSInfo strWps; + m2m_memset((uint8*)&strWps,0,sizeof(tstrM2MWPSInfo)); + if(hif_receive(u32Addr, (uint8*)&strWps, sizeof(tstrM2MWPSInfo), 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_REQ_WPS, &strWps); + } + } + else if (u8OpCode == M2M_WIFI_RESP_IP_CONFLICT) + { + uint32 u32ConflictedIP; + if(hif_receive(u32Addr, (uint8 *)&u32ConflictedIP, sizeof(u32ConflictedIP), 0) == M2M_SUCCESS) + { + M2M_INFO("Conflicted IP \" %u.%u.%u.%u \" \n", + BYTE_0(u32ConflictedIP),BYTE_1(u32ConflictedIP),BYTE_2(u32ConflictedIP),BYTE_3(u32ConflictedIP)); + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_IP_CONFLICT, NULL); + + } + } + else if (u8OpCode == M2M_WIFI_RESP_SCAN_DONE) + { + tstrM2mScanDone strState; + gu8scanInProgress = 0; + if(hif_receive(u32Addr, (uint8*)&strState, sizeof(tstrM2mScanDone), 0) == M2M_SUCCESS) + { + gu8ChNum = strState.u8NumofCh; + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_SCAN_DONE, &strState); + } + } + else if (u8OpCode == M2M_WIFI_RESP_SCAN_RESULT) + { + tstrM2mWifiscanResult strScanResult; + if(hif_receive(u32Addr, (uint8*)&strScanResult, sizeof(tstrM2mWifiscanResult), 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_SCAN_RESULT, &strScanResult); + } + } + else if (u8OpCode == M2M_WIFI_RESP_CURRENT_RSSI) + { + if (hif_receive(u32Addr, rx_buf, 4, 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_CURRENT_RSSI, rx_buf); + } + } + else if (u8OpCode == M2M_WIFI_RESP_CLIENT_INFO) + { + if (hif_receive(u32Addr, rx_buf, 4, 0) == M2M_SUCCESS) + { + if (gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_CLIENT_INFO, rx_buf); + } + } + else if(u8OpCode == M2M_WIFI_RESP_PROVISION_INFO) + { + tstrM2MProvisionInfo strProvInfo; + if(hif_receive(u32Addr, (uint8*)&strProvInfo, sizeof(tstrM2MProvisionInfo), 1) == M2M_SUCCESS) + { + if(gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_PROVISION_INFO, &strProvInfo); + } + } + else if(u8OpCode == M2M_WIFI_RESP_DEFAULT_CONNECT) + { + tstrM2MDefaultConnResp strResp; + if(hif_receive(u32Addr, (uint8*)&strResp, sizeof(tstrM2MDefaultConnResp), 1) == M2M_SUCCESS) + { + if(gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_DEFAULT_CONNECT, &strResp); + } + } + + else if(u8OpCode == M2M_WIFI_RESP_GET_PRNG) + { + tstrPrng strPrng; + if(hif_receive(u32Addr, (uint8*)&strPrng,sizeof(tstrPrng), 0) == M2M_SUCCESS) + { + if(hif_receive(u32Addr + sizeof(tstrPrng),strPrng.pu8RngBuff,strPrng.u16PrngSize, 1) == M2M_SUCCESS) + { + if(gpfAppWifiCb) + gpfAppWifiCb(M2M_WIFI_RESP_GET_PRNG,&strPrng); + } + } + } +#ifdef ETH_MODE + else if(u8OpCode == M2M_WIFI_RESP_ETHERNET_RX_PACKET) + { + uint8 u8SetRxDone; + tstrM2mIpRsvdPkt strM2mRsvd; + if(hif_receive(u32Addr, &strM2mRsvd ,sizeof(tstrM2mIpRsvdPkt), 0) == M2M_SUCCESS) + { + tstrM2mIpCtrlBuf strM2mIpCtrlBuf; + uint16 u16Offset = strM2mRsvd.u16PktOffset; + strM2mIpCtrlBuf.u16RemainigDataSize = strM2mRsvd.u16PktSz; + if((gpfAppEthCb) && (gau8ethRcvBuf) && (gu16ethRcvBufSize > 0)) + { + do + { + u8SetRxDone = 1; + if(strM2mIpCtrlBuf.u16RemainigDataSize > gu16ethRcvBufSize) + { + u8SetRxDone = 0; + strM2mIpCtrlBuf.u16DataSize = gu16ethRcvBufSize; + } + else + { + strM2mIpCtrlBuf.u16DataSize = strM2mIpCtrlBuf.u16RemainigDataSize; + } + + if(hif_receive(u32Addr + u16Offset, gau8ethRcvBuf, strM2mIpCtrlBuf.u16DataSize, u8SetRxDone) == M2M_SUCCESS) + { + strM2mIpCtrlBuf.u16RemainigDataSize -= strM2mIpCtrlBuf.u16DataSize; + u16Offset += strM2mIpCtrlBuf.u16DataSize; + gpfAppEthCb(M2M_WIFI_RESP_ETHERNET_RX_PACKET, gau8ethRcvBuf, &(strM2mIpCtrlBuf)); + } + else + { + break; + } + }while (strM2mIpCtrlBuf.u16RemainigDataSize > 0); + } + } + } +#endif /* ETH_MODE */ +#ifdef CONF_MGMT + else if(u8OpCode == M2M_WIFI_RESP_WIFI_RX_PACKET) + { + + tstrM2MWifiRxPacketInfo strRxPacketInfo; + if(u16DataSize >= sizeof(tstrM2MWifiRxPacketInfo)) { + if(hif_receive(u32Addr, (uint8*)&strRxPacketInfo, sizeof(tstrM2MWifiRxPacketInfo), 0) == M2M_SUCCESS) + { + u16DataSize -= sizeof(tstrM2MWifiRxPacketInfo); + if(u16DataSize > 0 && gstrMgmtCtrl.pu8Buf != NULL) + { + if(u16DataSize > (gstrMgmtCtrl.u16Sz + gstrMgmtCtrl.u16Offset)) + { + u16DataSize = gstrMgmtCtrl.u16Sz; + } + u32Addr += sizeof(tstrM2MWifiRxPacketInfo) + gstrMgmtCtrl.u16Offset; + if(hif_receive(u32Addr , gstrMgmtCtrl.pu8Buf, u16DataSize, 1) != M2M_SUCCESS) return; + } + if(gpfAppMonCb) + gpfAppMonCb(&strRxPacketInfo, gstrMgmtCtrl.pu8Buf,u16DataSize); + } + } else { + M2M_ERR("Incorrect mon data size %u\n", u16DataSize); + } + } +#endif + else + { + M2M_ERR("REQ Not defined %d\n",u8OpCode); + } +} + +sint8 m2m_wifi_download_mode() +{ + sint8 ret = M2M_SUCCESS; + /* Apply device specific initialization. */ + ret = nm_drv_init_download_mode(); + if(ret != M2M_SUCCESS) goto _EXIT0; + + + + enable_interrupts(); + +_EXIT0: + return ret; +} + +static sint8 m2m_validate_ap_parameters(CONST tstrM2MAPConfig* pstrM2MAPConfig) +{ + sint8 s8Ret = M2M_SUCCESS; + /* Check for incoming pointer */ + if(pstrM2MAPConfig == NULL) + { + M2M_ERR("INVALID POINTER\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + /* Check for SSID */ + if((m2m_strlen((uint8 *)pstrM2MAPConfig->au8SSID) <= 0) || (m2m_strlen((uint8 *)pstrM2MAPConfig->au8SSID) >= M2M_MAX_SSID_LEN)) + { + M2M_ERR("INVALID SSID\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + /* Check for Channel */ + if(pstrM2MAPConfig->u8ListenChannel > M2M_WIFI_CH_14 || pstrM2MAPConfig->u8ListenChannel < M2M_WIFI_CH_1) + { + M2M_ERR("INVALID CH\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + /* Check for DHCP Server IP address */ + if(!(pstrM2MAPConfig->au8DHCPServerIP[0] || pstrM2MAPConfig->au8DHCPServerIP[1])) + { + if(!(pstrM2MAPConfig->au8DHCPServerIP[2])) + { + M2M_ERR("INVALID DHCP SERVER IP\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + } + /* Check for Security */ + if(pstrM2MAPConfig->u8SecType == M2M_WIFI_SEC_OPEN) + { + goto ERR1; + } + else if(pstrM2MAPConfig->u8SecType == M2M_WIFI_SEC_WEP) + { + /* Check for WEP Key index */ + if((pstrM2MAPConfig->u8KeyIndx <= 0) || (pstrM2MAPConfig->u8KeyIndx > WEP_KEY_MAX_INDEX)) + { + M2M_ERR("INVALID KEY INDEX\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + /* Check for WEP Key size */ + if( (pstrM2MAPConfig->u8KeySz != WEP_40_KEY_STRING_SIZE) && + (pstrM2MAPConfig->u8KeySz != WEP_104_KEY_STRING_SIZE) + ) + { + M2M_ERR("INVALID KEY SIZE\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + /* Check for WEP Key */ + if((pstrM2MAPConfig->au8WepKey == NULL) || (m2m_strlen((uint8 *)pstrM2MAPConfig->au8WepKey) <= 0) || (m2m_strlen((uint8 *)pstrM2MAPConfig->au8WepKey) > WEP_104_KEY_STRING_SIZE)) + { + M2M_ERR("INVALID WEP KEY\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + } + else + { + M2M_ERR("INVALID AUTHENTICATION MODE\n"); + s8Ret = M2M_ERR_FAIL; + goto ERR1; + } + +ERR1: + return s8Ret; +} + +static sint8 m2m_validate_scan_options(tstrM2MScanOption* ptstrM2MScanOption) +{ + sint8 s8Ret = M2M_SUCCESS; + /* Check for incoming pointer */ + if(ptstrM2MScanOption == NULL) + { + M2M_ERR("INVALID POINTER\n"); + s8Ret = M2M_ERR_FAIL; + } + /* Check for valid No of slots */ + if(ptstrM2MScanOption->u8NumOfSlot < 1) + { + M2M_ERR("INVALID No of scan slots!\n"); + s8Ret = M2M_ERR_FAIL; + } + /* Check for valid time of slots */ + if(ptstrM2MScanOption->u8SlotTime < 1) + { + M2M_ERR("INVALID scan slot time!\n"); + s8Ret = M2M_ERR_FAIL; + } + /* Check for valid No of probe requests per slot */ + if((ptstrM2MScanOption->u8ProbesPerSlot < 0)||(ptstrM2MScanOption->u8ProbesPerSlot > M2M_SCAN_DEFAULT_NUM_PROBE)) + { + M2M_ERR("INVALID No of probe requests per scan slot\n"); + s8Ret = M2M_ERR_FAIL; + } + /* Check for valid RSSI threshold */ + if((ptstrM2MScanOption->s8RssiThresh < -99) || (ptstrM2MScanOption->s8RssiThresh >= 0)) + { + M2M_ERR("INVALID RSSI threshold %d \n",ptstrM2MScanOption->s8RssiThresh); + s8Ret = M2M_ERR_FAIL; + } + return s8Ret; +} + +sint8 m2m_wifi_init(tstrWifiInitParam * param) +{ + tstrM2mRev strtmp; + sint8 ret = M2M_SUCCESS; + uint8 u8WifiMode = M2M_WIFI_MODE_NORMAL; + + if(param == NULL) { + ret = M2M_ERR_FAIL; + goto _EXIT0; + } + + gpfAppWifiCb = param->pfAppWifiCb; + +#ifdef ETH_MODE + gpfAppEthCb = param->strEthInitParam.pfAppEthCb; + gau8ethRcvBuf = param->strEthInitParam.au8ethRcvBuf; + gu16ethRcvBufSize = param->strEthInitParam.u16ethRcvBufSize; + u8WifiMode = param->strEthInitParam.u8EthernetEnable; +#endif /* ETH_MODE */ + +#ifdef CONF_MGMT + gpfAppMonCb = param->pfAppMonCb; +#endif + gu8scanInProgress = 0; + /* Apply device specific initialization. */ + ret = nm_drv_init(&u8WifiMode); + if(ret != M2M_SUCCESS) goto _EXIT0; + /* Initialize host interface module */ + ret = hif_init(NULL); + if(ret != M2M_SUCCESS) goto _EXIT1; + + hif_register_cb(M2M_REQ_GROUP_WIFI,m2m_wifi_cb); + + ret = nm_get_firmware_info(&strtmp); + + M2M_INFO("Firmware ver : %u.%u.%u\n", strtmp.u8FirmwareMajor, strtmp.u8FirmwareMinor, strtmp.u8FirmwarePatch); + M2M_INFO("Min driver ver : %u.%u.%u\n", strtmp.u8DriverMajor, strtmp.u8DriverMinor, strtmp.u8DriverPatch); + M2M_INFO("Curr driver ver: %u.%u.%u\n", M2M_DRIVER_VERSION_MAJOR_NO, M2M_DRIVER_VERSION_MINOR_NO, M2M_DRIVER_VERSION_PATCH_NO); + if(M2M_ERR_FW_VER_MISMATCH == ret) + { + M2M_ERR("Mismatch Firmawre Version\n"); + } + + goto _EXIT0; + +_EXIT1: + nm_drv_deinit(NULL); +_EXIT0: + return ret; +} + +sint8 m2m_wifi_deinit(void * arg) +{ + + hif_deinit(NULL); + + nm_drv_deinit(NULL); + + return M2M_SUCCESS; +} + + +sint8 m2m_wifi_handle_events(void * arg) +{ + return hif_handle_isr(); +} + +sint8 m2m_wifi_default_connect(void) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DEFAULT_CONNECT, NULL, 0,NULL, 0,0); +} + +sint8 m2m_wifi_connect(char *pcSsid, uint8 u8SsidLen, uint8 u8SecType, void *pvAuthInfo, uint16 u16Ch) +{ + return m2m_wifi_connect_sc(pcSsid, u8SsidLen, u8SecType, pvAuthInfo, u16Ch,0); +} +sint8 m2m_wifi_connect_sc(char *pcSsid, uint8 u8SsidLen, uint8 u8SecType, void *pvAuthInfo, uint16 u16Ch, uint8 u8NoSaveCred) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mWifiConnect strConnect; + tstrM2MWifiSecInfo *pstrAuthInfo; + + if(u8SecType != M2M_WIFI_SEC_OPEN) + { + if(pvAuthInfo == NULL) + { + M2M_ERR("Key is not valid\n"); + ret = M2M_ERR_FAIL; + goto ERR1; + } + if((u8SecType == M2M_WIFI_SEC_WPA_PSK) && (m2m_strlen(pvAuthInfo) == (M2M_MAX_PSK_LEN-1))) + { + uint8 i = 0; + uint8* pu8Psk = (uint8*)pvAuthInfo; + while(i < (M2M_MAX_PSK_LEN-1)) + { + if(pu8Psk[i]<'0' || (pu8Psk[i]>'9' && pu8Psk[i] < 'A')|| (pu8Psk[i]>'F' && pu8Psk[i] < 'a') || pu8Psk[i] > 'f') + { + M2M_ERR("Invalid Key\n"); + ret = M2M_ERR_FAIL; + goto ERR1; + } + i++; + } + } + } + if((u8SsidLen<=0)||(u8SsidLen>=M2M_MAX_SSID_LEN)) + { + M2M_ERR("SSID LEN INVALID\n"); + ret = M2M_ERR_FAIL; + goto ERR1; + } + + if(u16Ch>M2M_WIFI_CH_14) + { + if(u16Ch!=M2M_WIFI_CH_ALL) + { + M2M_ERR("CH INVALID\n"); + ret = M2M_ERR_FAIL; + goto ERR1; + } + } + + + m2m_memcpy(strConnect.au8SSID, (uint8*)pcSsid, u8SsidLen); + strConnect.au8SSID[u8SsidLen] = 0; + strConnect.u16Ch = NM_BSP_B_L_16(u16Ch); + /* Credentials will be Not be saved if u8NoSaveCred is set */ + strConnect.u8NoSaveCred = u8NoSaveCred ? 1:0; + pstrAuthInfo = &strConnect.strSec; + pstrAuthInfo->u8SecType = u8SecType; + + if(u8SecType == M2M_WIFI_SEC_WEP) + { + tstrM2mWifiWepParams * pstrWepParams = (tstrM2mWifiWepParams*)pvAuthInfo; + tstrM2mWifiWepParams *pstrWep = &pstrAuthInfo->uniAuth.strWepInfo; + pstrWep->u8KeyIndx =pstrWepParams->u8KeyIndx-1; + + if(pstrWep->u8KeyIndx >= WEP_KEY_MAX_INDEX) + { + M2M_ERR("Invalid Wep key index %d\n", pstrWep->u8KeyIndx); + ret = M2M_ERR_FAIL; + goto ERR1; + } + pstrWep->u8KeySz = pstrWepParams->u8KeySz-1; + if ((pstrWep->u8KeySz != WEP_40_KEY_STRING_SIZE)&& (pstrWep->u8KeySz != WEP_104_KEY_STRING_SIZE)) + { + M2M_ERR("Invalid Wep key length %d\n", pstrWep->u8KeySz); + ret = M2M_ERR_FAIL; + goto ERR1; + } + m2m_memcpy((uint8*)pstrWep->au8WepKey,(uint8*)pstrWepParams->au8WepKey, pstrWepParams->u8KeySz); + pstrWep->au8WepKey[pstrWepParams->u8KeySz] = 0; + + } + + + else if(u8SecType == M2M_WIFI_SEC_WPA_PSK) + { + uint16 u16KeyLen = m2m_strlen((uint8*)pvAuthInfo); + if((u16KeyLen <= 0)||(u16KeyLen >= M2M_MAX_PSK_LEN)) + { + M2M_ERR("Incorrect PSK key length\n"); + ret = M2M_ERR_FAIL; + goto ERR1; + } + m2m_memcpy(pstrAuthInfo->uniAuth.au8PSK, (uint8*)pvAuthInfo, u16KeyLen + 1); + } + else if(u8SecType == M2M_WIFI_SEC_802_1X) + { + m2m_memcpy((uint8*)&pstrAuthInfo->uniAuth.strCred1x, (uint8*)pvAuthInfo, sizeof(tstr1xAuthCredentials)); + } + else if(u8SecType == M2M_WIFI_SEC_OPEN) + { + + } + else + { + M2M_ERR("undefined sec type\n"); + ret = M2M_ERR_FAIL; + goto ERR1; + } + + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_CONNECT, (uint8*)&strConnect, sizeof(tstrM2mWifiConnect),NULL, 0,0); + +ERR1: + return ret; +} + +sint8 m2m_wifi_disconnect(void) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DISCONNECT, NULL, 0, NULL, 0,0); +} +sint8 m2m_wifi_set_mac_address(uint8 au8MacAddress[6]) +{ + tstrM2mSetMacAddress strTmp; + m2m_memcpy((uint8*) strTmp.au8Mac, (uint8*) au8MacAddress, 6); + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_MAC_ADDRESS, + (uint8*) &strTmp, sizeof(tstrM2mSetMacAddress), NULL, 0,0); +} + +sint8 m2m_wifi_set_static_ip(tstrM2MIPConfig * pstrStaticIPConf) +{ + pstrStaticIPConf->u32DNS = NM_BSP_B_L_32(pstrStaticIPConf->u32DNS); + pstrStaticIPConf->u32Gateway = NM_BSP_B_L_32(pstrStaticIPConf->u32Gateway); + pstrStaticIPConf->u32StaticIP = NM_BSP_B_L_32( + pstrStaticIPConf->u32StaticIP); + pstrStaticIPConf->u32SubnetMask = NM_BSP_B_L_32( + pstrStaticIPConf->u32SubnetMask); + return hif_send(M2M_REQ_GROUP_IP, M2M_IP_REQ_STATIC_IP_CONF, + (uint8*) pstrStaticIPConf, sizeof(tstrM2MIPConfig), NULL, 0,0); +} + +sint8 m2m_wifi_request_dhcp_client(void) +{ + /*legacy API should be removed */ + return 0; +} +sint8 m2m_wifi_request_dhcp_server(uint8* addr) +{ + /*legacy API should be removed */ + return 0; +} +/*! +@fn NMI_API sint8 m2m_wifi_set_lsn_int(tstrM2mLsnInt * pstrM2mLsnInt); +@brief Set the Wi-Fi listen interval for power save operation. It is represented in units + of AP Beacon periods. +@param [in] pstrM2mLsnInt + Structure holding the listen interval configurations. +@return The function SHALL return 0 for success and a negative value otherwise. +@sa tstrM2mLsnInt , m2m_wifi_set_sleep_mode +@pre m2m_wifi_set_sleep_mode shall be called first +@warning The Function called once after initialization. +*/ +sint8 m2m_wifi_enable_dhcp(uint8 u8DhcpEn ) +{ + + uint8 u8Req; + u8Req = u8DhcpEn ? M2M_IP_REQ_ENABLE_DHCP : M2M_IP_REQ_DISABLE_DHCP; + return hif_send(M2M_REQ_GROUP_IP, u8Req, NULL, 0, NULL, 0, 0); + + +} + +sint8 m2m_wifi_set_lsn_int(tstrM2mLsnInt* pstrM2mLsnInt) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_LSN_INT, (uint8*)pstrM2mLsnInt, sizeof(tstrM2mLsnInt), NULL, 0, 0); +} + +sint8 m2m_wifi_set_cust_InfoElement(uint8* pau8M2mCustInfoElement) +{ + + sint8 ret = M2M_ERR_FAIL; + if(pau8M2mCustInfoElement != NULL) + { + if((pau8M2mCustInfoElement[0] + 1) < M2M_CUST_IE_LEN_MAX) + { + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_CUST_INFO_ELEMENT|M2M_REQ_DATA_PKT, (uint8*)pau8M2mCustInfoElement, pau8M2mCustInfoElement[0]+1, NULL, 0, 0); + } + } + return ret; +} + +sint8 m2m_wifi_set_scan_options(tstrM2MScanOption* ptstrM2MScanOption) +{ + sint8 s8Ret = M2M_ERR_FAIL; + if(m2m_validate_scan_options (ptstrM2MScanOption) == M2M_SUCCESS) + { + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_SCAN_OPTION, (uint8*)ptstrM2MScanOption, sizeof(tstrM2MScanOption),NULL, 0,0); + } + return s8Ret; +} +sint8 m2m_wifi_set_scan_region(uint16 ScanRegion) +{ + sint8 s8Ret = M2M_ERR_FAIL; + tstrM2MScanRegion strScanRegion; + strScanRegion.u16ScanRegion = ScanRegion; + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_SCAN_REGION, (uint8*)&strScanRegion, sizeof(tstrM2MScanRegion),NULL, 0,0); + return s8Ret; +} +sint8 m2m_wifi_request_scan(uint8 ch) +{ + sint8 s8Ret = M2M_SUCCESS; + + if(!gu8scanInProgress) + { + if(((ch >= M2M_WIFI_CH_1) && (ch <= M2M_WIFI_CH_14)) || (ch == M2M_WIFI_CH_ALL)) + { + tstrM2MScan strtmp; + strtmp.u8ChNum = ch; + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SCAN, (uint8*)&strtmp, sizeof(tstrM2MScan),NULL, 0,0); + if(s8Ret == M2M_SUCCESS) + { + gu8scanInProgress = 1; + } + } + else + { + s8Ret = M2M_ERR_INVALID_ARG; + } + } + else + { + s8Ret = M2M_ERR_SCAN_IN_PROGRESS; + } + return s8Ret; +} +sint8 m2m_wifi_wps(uint8 u8TriggerType,const char *pcPinNumber) +{ + tstrM2MWPSConnect strtmp; + + /* Stop Scan if it is ongoing. + */ + gu8scanInProgress = 0; + strtmp.u8TriggerType = u8TriggerType; + /*If WPS is using PIN METHOD*/ + if (u8TriggerType == WPS_PIN_TRIGGER) + m2m_memcpy ((uint8*)strtmp.acPinNumber,(uint8*) pcPinNumber,8); + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_WPS, (uint8*)&strtmp,sizeof(tstrM2MWPSConnect), NULL, 0,0); +} +sint8 m2m_wifi_wps_disable(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DISABLE_WPS, NULL,0, NULL, 0, 0); + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_req_client_ctrl(uint8 cmd); +@brief Send a command to the PS Client (An WINC1500 board running the ps_firmware), + if the PS client send any commands it will be received in wifi_cb M2M_WIFI_RESP_CLIENT_INFO +@param [in] cmd + Control command sent from PS Server to PS Client (command values defined by the application) +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa m2m_wifi_req_server_init, M2M_WIFI_RESP_CLIENT_INFO +@pre m2m_wifi_req_server_init should be called first +@warning +*/ +sint8 m2m_wifi_req_client_ctrl(uint8 u8Cmd) +{ + + sint8 ret = M2M_SUCCESS; +#ifdef _PS_SERVER_ + tstrM2Mservercmd strCmd; + strCmd.u8cmd = u8Cmd; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_CLIENT_CTRL, (uint8*)&strCmd, sizeof(tstrM2Mservercmd), NULL, 0, 0); +#else + M2M_ERR("_PS_SERVER_ is not defined\n"); +#endif + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_req_server_init(uint8 ch); +@brief Initialize the PS Server, The WINC1500 support Non secure communication with another WINC1500, + (SERVER/CLIENT) through one byte command (probe request and probe response) without any connection setup +@param [in] ch + Server listening channel +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise +@sa m2m_wifi_req_client_ctrl +@warning The server mode can't be used with any other modes (STA/P2P/AP) +*/ +sint8 m2m_wifi_req_server_init(uint8 ch) +{ + sint8 ret = M2M_SUCCESS; +#ifdef _PS_SERVER_ + tstrM2mServerInit strServer; + strServer.u8Channel = ch; + ret = hif_send(M2M_REQ_GROUP_WIFI,M2M_WIFI_REQ_SERVER_INIT, (uint8*)&strServer, sizeof(tstrM2mServerInit), NULL, 0, 0); +#else + M2M_ERR("_PS_SERVER_ is not defined\n"); +#endif + return ret; +} +sint8 m2m_wifi_p2p(uint8 u8Channel) +{ + sint8 ret = M2M_SUCCESS; + if((u8Channel == M2M_WIFI_CH_1) || (u8Channel == M2M_WIFI_CH_6) || (u8Channel == M2M_WIFI_CH_11)) + { + tstrM2MP2PConnect strtmp; + strtmp.u8ListenChannel = u8Channel; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_ENABLE_P2P, (uint8*)&strtmp, sizeof(tstrM2MP2PConnect), NULL, 0,0); + } + else + { + M2M_ERR("Listen channel should only be 1, 6 or 11\n"); + ret = M2M_ERR_FAIL; + } + return ret; +} +sint8 m2m_wifi_p2p_disconnect(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DISABLE_P2P, NULL, 0, NULL, 0, 0); + return ret; +} +sint8 m2m_wifi_enable_ap(CONST tstrM2MAPConfig* pstrM2MAPConfig) +{ + sint8 ret = M2M_ERR_FAIL; + if(M2M_SUCCESS == m2m_validate_ap_parameters(pstrM2MAPConfig)) + { + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_ENABLE_AP, (uint8 *)pstrM2MAPConfig, sizeof(tstrM2MAPConfig), NULL, 0, 0); + } + return ret; +} +sint8 m2m_wifi_disable_ap(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DISABLE_AP, NULL, 0, NULL, 0, 0); + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_req_curr_rssi(void); +@brief Request the current RSSI for the current connected AP, + the response received in wifi_cb M2M_WIFI_RESP_CURRENT_RSSI +@sa M2M_WIFI_RESP_CURRENT_RSSI +@return The function shall return M2M_SUCCESS for success and a negative value otherwise. +*/ +sint8 m2m_wifi_req_curr_rssi(void) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_CURRENT_RSSI, NULL, 0, NULL,0, 0); + return ret; +} +sint8 m2m_wifi_send_ethernet_pkt(uint8* pu8Packet,uint16 u16PacketSize) +{ + sint8 s8Ret = -1; + if((pu8Packet != NULL)&&(u16PacketSize>0)) + { + tstrM2MWifiTxPacketInfo strTxPkt; + + strTxPkt.u16PacketSize = u16PacketSize; + strTxPkt.u16HeaderLength = M2M_ETHERNET_HDR_LEN; + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SEND_ETHERNET_PACKET | M2M_REQ_DATA_PKT, + (uint8*)&strTxPkt, sizeof(tstrM2MWifiTxPacketInfo), pu8Packet, u16PacketSize, M2M_ETHERNET_HDR_OFFSET - M2M_HIF_HDR_OFFSET); + } + return s8Ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_get_otp_mac_address(uint8 *pu8MacAddr, uint8 * pu8IsValid); +@brief Request the MAC address stored on the OTP (one time programmable) memory of the device. + (the function is Blocking until response received) +@param [out] pu8MacAddr + Output MAC address buffer of 6 bytes size. Valid only if *pu8Valid=1. +@param [out] pu8IsValid + A output boolean value to indicate the validity of pu8MacAddr in OTP. + Output zero if the OTP memory is not programmed, non-zero otherwise. +@return The function shall return M2M_SUCCESS for success and a negative value otherwise. +@sa m2m_wifi_get_mac_address +@pre m2m_wifi_init required to call any WIFI/socket function +*/ +sint8 m2m_wifi_get_otp_mac_address(uint8 *pu8MacAddr, uint8* pu8IsValid) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_chip_wake(); + if(ret == M2M_SUCCESS) + { + ret = nmi_get_otp_mac_address(pu8MacAddr, pu8IsValid); + if(ret == M2M_SUCCESS) + { + ret = hif_chip_sleep(); + } + } + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_get_mac_address(uint8 *pu8MacAddr) +@brief Request the current MAC address of the device (the working mac address). + (the function is Blocking until response received) +@param [out] pu8MacAddr + Output MAC address buffer of 6 bytes size. +@return The function shall return M2M_SUCCESS for success and a negative value otherwise. +@sa m2m_wifi_get_otp_mac_address +@pre m2m_wifi_init required to call any WIFI/socket function +*/ +sint8 m2m_wifi_get_mac_address(uint8 *pu8MacAddr) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_chip_wake(); + if(ret == M2M_SUCCESS) + { + ret = nmi_get_mac_address(pu8MacAddr); + if(ret == M2M_SUCCESS) + { + ret = hif_chip_sleep(); + } + } + + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_req_scan_result(uint8 index); +@brief Reads the AP information from the Scan Result list with the given index, + the response received in wifi_cb M2M_WIFI_RESP_SCAN_RESULT, + the response pointer should be casted with tstrM2mWifiscanResult structure +@param [in] index + Index for the requested result, the index range start from 0 till number of AP's found +@sa tstrM2mWifiscanResult,m2m_wifi_get_num_ap_found,m2m_wifi_request_scan +@return The function shall return M2M_SUCCESE for success and a negative value otherwise +@pre m2m_wifi_request_scan need to be called first, then m2m_wifi_get_num_ap_found + to get the number of AP's found +@warning Function used only in STA mode only. the scan result updated only if scan request called, + else it will be cashed in firmware for the host scan request result, + which mean if large delay occur between the scan request and the scan result request, + the result will not be up-to-date +*/ + +sint8 m2m_wifi_req_scan_result(uint8 index) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mReqScanResult strReqScanRlt; + strReqScanRlt.u8Index = index; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SCAN_RESULT, (uint8*) &strReqScanRlt, sizeof(tstrM2mReqScanResult), NULL, 0, 0); + return ret; +} +/*! +@fn NMI_API uint8 m2m_wifi_get_num_ap_found(void); +@brief Reads the number of AP's found in the last Scan Request, + The function read the number of AP's from global variable which updated in the + wifi_cb in M2M_WIFI_RESP_SCAN_DONE. +@sa m2m_wifi_request_scan +@return Return the number of AP's found in the last Scan Request. +@pre m2m_wifi_request_scan need to be called first +@warning That function need to be called in the wifi_cb in M2M_WIFI_RESP_SCAN_DONE, + calling that function in any other place will return undefined/undated numbers. + Function used only in STA mode only. +*/ +uint8 m2m_wifi_get_num_ap_found(void) +{ + return gu8ChNum; +} +/*! +@fn NMI_API uint8 m2m_wifi_get_sleep_mode(void); +@brief Get the current Power save mode. +@return The current operating power saving mode. +@sa tenuPowerSaveModes , m2m_wifi_set_sleep_mode +*/ +uint8 m2m_wifi_get_sleep_mode(void) +{ + return hif_get_sleep_mode(); +} +/*! +@fn NMI_API sint8 m2m_wifi_set_sleep_mode(uint8 PsTyp, uint8 BcastEn); +@brief Set the power saving mode for the WINC1500. +@param [in] PsTyp + Desired power saving mode. Supported types are defined in tenuPowerSaveModes. +@param [in] BcastEn + Broadcast reception enable flag. + If it is 1, the WINC1500 must be awake each DTIM Beacon for receiving Broadcast traffic. + If it is 0, the WINC1500 will not wakeup at the DTIM Beacon, but its wakeup depends only + on the the configured Listen Interval. +@return The function SHALL return 0 for success and a negative value otherwise. +@sa tenuPowerSaveModes +@warning The function called once after initialization. +*/ +sint8 m2m_wifi_set_sleep_mode(uint8 PsTyp, uint8 BcastEn) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mPsType strPs; + strPs.u8PsType = PsTyp; + strPs.u8BcastEn = BcastEn; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SLEEP, (uint8*) &strPs,sizeof(tstrM2mPsType), NULL, 0, 0); + M2M_INFO("POWER SAVE %d\n",PsTyp); + hif_set_sleep_mode(PsTyp); + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_request_sleep(void) +@brief Request from WINC1500 device to Sleep for specific time in the M2M_PS_MANUAL Power save mode (only). +@param [in] u32SlpReqTime + Request Sleep in ms +@return The function SHALL return M2M_SUCCESS for success and a negative value otherwise. +@sa tenuPowerSaveModes , m2m_wifi_set_sleep_mode +@warning the Function should be called in M2M_PS_MANUAL power save only +*/ +sint8 m2m_wifi_request_sleep(uint32 u32SlpReqTime) +{ + sint8 ret = M2M_SUCCESS; + uint8 psType; + psType = hif_get_sleep_mode(); + if(psType == M2M_PS_MANUAL) + { + tstrM2mSlpReqTime strPs; + strPs.u32SleepTime = u32SlpReqTime; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DOZE, (uint8*) &strPs,sizeof(tstrM2mSlpReqTime), NULL, 0, 0); + } + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_set_device_name(uint8 *pu8DeviceName, uint8 u8DeviceNameLength); +@brief Set the WINC1500 device name which is used as P2P device name. +@param [in] pu8DeviceName + Buffer holding the device name. +@param [in] u8DeviceNameLength + Length of the device name. +@return The function SHALL return M2M_SUCCESS for success and a negative value otherwise. +@warning The Function called once after initialization. +*/ +sint8 m2m_wifi_set_device_name(uint8 *pu8DeviceName, uint8 u8DeviceNameLength) +{ + tstrM2MDeviceNameConfig strDeviceName; + if(u8DeviceNameLength >= M2M_DEVICE_NAME_MAX) + { + u8DeviceNameLength = M2M_DEVICE_NAME_MAX; + } + //pu8DeviceName[u8DeviceNameLength] = '\0'; + u8DeviceNameLength ++; + m2m_memcpy(strDeviceName.au8DeviceName, pu8DeviceName, u8DeviceNameLength); + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_DEVICE_NAME, + (uint8*)&strDeviceName, sizeof(tstrM2MDeviceNameConfig), NULL, 0,0); +} +sint8 m2m_wifi_get_firmware_version(tstrM2mRev *pstrRev) +{ + sint8 ret = M2M_SUCCESS; + ret = hif_chip_wake(); + if(ret == M2M_SUCCESS) + { + ret = nm_get_firmware_full_info(pstrRev); + hif_chip_sleep(); + } + return ret; +} +#ifdef CONF_MGMT +sint8 m2m_wifi_enable_monitoring_mode(tstrM2MWifiMonitorModeCtrl *pstrMtrCtrl, uint8 *pu8PayloadBuffer, + uint16 u16BufferSize, uint16 u16DataOffset) +{ + sint8 s8Ret = -1; + if((pstrMtrCtrl->u8ChannelID >= M2M_WIFI_CH_1) && (pstrMtrCtrl->u8ChannelID <= M2M_WIFI_CH_14)) + { + gstrMgmtCtrl.pu8Buf = pu8PayloadBuffer; + gstrMgmtCtrl.u16Sz = u16BufferSize; + gstrMgmtCtrl.u16Offset = u16DataOffset; + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_ENABLE_MONITORING, + (uint8*)pstrMtrCtrl, sizeof(tstrM2MWifiMonitorModeCtrl), NULL, 0,0); + } + return s8Ret; +} + +sint8 m2m_wifi_disable_monitoring_mode(void) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_DISABLE_MONITORING, NULL, 0, NULL, 0,0); +} + +sint8 m2m_wifi_send_wlan_pkt(uint8 *pu8WlanPacket, uint16 u16WlanHeaderLength, uint16 u16WlanPktSize) +{ + sint8 s8Ret = -1; + if(pu8WlanPacket != NULL) + { + tstrM2MWifiTxPacketInfo strTxPkt; + + strTxPkt.u16PacketSize = u16WlanPktSize; + strTxPkt.u16HeaderLength = u16WlanHeaderLength; + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SEND_WIFI_PACKET | M2M_REQ_DATA_PKT, + (uint8*)&strTxPkt, sizeof(tstrM2MWifiTxPacketInfo), pu8WlanPacket, u16WlanPktSize, sizeof(tstrM2MWifiTxPacketInfo)); + } + return s8Ret; +} +#endif + +sint8 m2m_wifi_start_provision_mode(tstrM2MAPConfig *pstrAPConfig, char *pcHttpServerDomainName, uint8 bEnableHttpRedirect) +{ + sint8 s8Ret = M2M_ERR_FAIL; + + if((pstrAPConfig != NULL)) + { + tstrM2MProvisionModeConfig strProvConfig; + if(M2M_SUCCESS == m2m_validate_ap_parameters(pstrAPConfig)) + { + m2m_memcpy((uint8*)&strProvConfig.strApConfig, (uint8*)pstrAPConfig, sizeof(tstrM2MAPConfig)); + if((m2m_strlen((uint8 *)pcHttpServerDomainName) <= 0) || (NULL == pcHttpServerDomainName)) + { + M2M_ERR("INVALID DOMAIN NAME\n"); + goto ERR1; + } + m2m_memcpy((uint8*)strProvConfig.acHttpServerDomainName, (uint8*)pcHttpServerDomainName, 64); + strProvConfig.u8EnableRedirect = bEnableHttpRedirect; + + /* Stop Scan if it is ongoing. + */ + gu8scanInProgress = 0; + s8Ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_START_PROVISION_MODE | M2M_REQ_DATA_PKT, + (uint8*)&strProvConfig, sizeof(tstrM2MProvisionModeConfig), NULL, 0, 0); + } + else + { + /*goto ERR1;*/ + } + } +ERR1: + return s8Ret; +} + +sint8 m2m_wifi_stop_provision_mode(void) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_STOP_PROVISION_MODE, NULL, 0, NULL, 0, 0); +} + +sint8 m2m_wifi_get_connection_info(void) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_GET_CONN_INFO, NULL, 0, NULL, 0, 0); +} + +sint8 m2m_wifi_set_sytem_time(uint32 u32UTCSeconds) +{ + /* + The firmware accepts timestamps relative to 1900 like NTP Timestamp. + */ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_SYS_TIME, (uint8*)&u32UTCSeconds, sizeof(tstrSystemTime), NULL, 0, 0); +} +/*! + * @fn NMI_API sint8 m2m_wifi_get_sytem_time(void); + * @see m2m_wifi_enable_sntp + tstrSystemTime + * @note get the system time from the sntp client + * using the API \ref m2m_wifi_get_sytem_time. + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +sint8 m2m_wifi_get_sytem_time(void) +{ + return hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_GET_SYS_TIME, NULL,0, NULL, 0, 0); +} + +sint8 m2m_wifi_enable_sntp(uint8 bEnable) +{ + uint8 u8Req; + + u8Req = bEnable ? M2M_WIFI_REQ_ENABLE_SNTP_CLIENT : M2M_WIFI_REQ_DISABLE_SNTP_CLIENT; + return hif_send(M2M_REQ_GROUP_WIFI, u8Req, NULL, 0, NULL, 0, 0); +} +/*! +@fn NMI_API sint8 m2m_wifi_set_power_profile(uint8 u8PwrMode); +@brief Change the power profile mode +@param [in] u8PwrMode + Change the WINC power profile to different mode + PWR_LOW1/PWR_LOW2/PWR_HIGH/PWR_AUTO (tenuM2mPwrMode) +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa tenuM2mPwrMode +@pre m2m_wifi_init +@warning must be called after the initializations and before any connection request and can't be changed in run time, +*/ +sint8 m2m_wifi_set_power_profile(uint8 u8PwrMode) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mPwrMode strM2mPwrMode; + strM2mPwrMode.u8PwrMode = u8PwrMode; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_POWER_PROFILE, (uint8*)&strM2mPwrMode,sizeof(tstrM2mPwrMode), NULL, 0, 0); + return ret; +} +/*! +@fn NMI_API sint8 m2m_wifi_set_tx_power(uint8 u8TxPwrLevel); +@brief set the TX power tenuM2mTxPwrLevel +@param [in] u8TxPwrLevel + change the TX power tenuM2mTxPwrLevel +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa tenuM2mTxPwrLevel +@pre m2m_wifi_init +@warning +*/ +sint8 m2m_wifi_set_tx_power(uint8 u8TxPwrLevel) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mTxPwrLevel strM2mTxPwrLevel; + strM2mTxPwrLevel.u8TxPwrLevel = u8TxPwrLevel; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_TX_POWER, (uint8*)&strM2mTxPwrLevel,sizeof(tstrM2mTxPwrLevel), NULL, 0, 0); + return ret; +} + +/*! +@fn NMI_API sint8 m2m_wifi_enable_firmware_logs(uint8 u8Enable); +@brief Enable or Disable logs in run time (Disable Firmware logs will + enhance the firmware start-up time and performance) +@param [in] u8Enable + Set 1 to enable the logs 0 for disable +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa __DISABLE_FIRMWARE_LOGS__ (build option to disable logs from initializations) +@pre m2m_wifi_init +@warning +*/ +sint8 m2m_wifi_enable_firmware_logs(uint8 u8Enable) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mEnableLogs strM2mEnableLogs; + strM2mEnableLogs.u8Enable = u8Enable; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_ENABLE_LOGS, (uint8*)&strM2mEnableLogs,sizeof(tstrM2mEnableLogs), NULL, 0, 0); + return ret; +} + +/*! +@fn NMI_API sint8 m2m_wifi_set_battery_voltage(uint16 u16BattVoltx100); +@brief Enable or Disable logs in run time (Disable Firmware logs will + enhance the firmware start-up time and performance) +@param [in] u16BattVoltx100 + battery voltage multiplied by 100 +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +@sa __DISABLE_FIRMWARE_LOGS__ (build option to disable logs from initializations) +@pre m2m_wifi_init +@warning +*/ +sint8 m2m_wifi_set_battery_voltage(uint16 u16BattVoltx100) +{ + sint8 ret = M2M_SUCCESS; + tstrM2mBatteryVoltage strM2mBattVol = {0}; + strM2mBattVol.u16BattVolt = u16BattVoltx100; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_BATTERY_VOLTAGE, (uint8*)&strM2mBattVol,sizeof(tstrM2mBatteryVoltage), NULL, 0, 0); + return ret; +} +/*! +@fn sint8 m2m_wifi_prng_get_random_bytes(uint8 * pu8PrngBuff,uint16 u16PrngSize) +@brief Get random bytes using the PRNG bytes. +@param [in] u16PrngSize + Size of the required random bytes to be generated. +@param [in] pu8PrngBuff + Pointer to user allocated buffer. +@return The function SHALL return M2M_SUCCESE for success and a negative value otherwise. +*/ +sint8 m2m_wifi_prng_get_random_bytes(uint8 * pu8PrngBuff,uint16 u16PrngSize) +{ + sint8 ret = M2M_ERR_FAIL; + tstrPrng strRng = {0}; + if((u16PrngSize < (M2M_BUFFER_MAX_SIZE - sizeof(tstrPrng)))&&(pu8PrngBuff != NULL)) + { + strRng.u16PrngSize = u16PrngSize; + strRng.pu8RngBuff = pu8PrngBuff; + ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_GET_PRNG|M2M_REQ_DATA_PKT,(uint8 *)&strRng, sizeof(tstrPrng),NULL,0, 0); + } + else + { + M2M_ERR("PRNG Buffer exceeded maximum size %d or NULL Buffer\n",u16PrngSize); + } + return ret; +} +#ifdef ETH_MODE +/*! +@fn \ + NMI_API sint8 m2m_wifi_enable_mac_mcast(uint8* pu8MulticastMacAddress, uint8 u8AddRemove) + +@brief + Add MAC filter to receive Multicast packets. + +@param [in] pu8MulticastMacAddress + Pointer to the MAC address. +@param [in] u8AddRemove + Flag to Add/Remove MAC address. +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ + +NMI_API sint8 m2m_wifi_enable_mac_mcast(uint8* pu8MulticastMacAddress, uint8 u8AddRemove) +{ + sint8 s8ret = M2M_ERR_FAIL; + tstrM2MMulticastMac strMulticastMac; + + if(pu8MulticastMacAddress != NULL ) + { + strMulticastMac.u8AddRemove = u8AddRemove; + m2m_memcpy(strMulticastMac.au8macaddress,pu8MulticastMacAddress,M2M_MAC_ADDRES_LEN); + M2M_DBG("mac multicast: %x:%x:%x:%x:%x:%x\r\n",strMulticastMac.au8macaddress[0],strMulticastMac.au8macaddress[1],strMulticastMac.au8macaddress[2],strMulticastMac.au8macaddress[3],strMulticastMac.au8macaddress[4],strMulticastMac.au8macaddress[5]); + s8ret = hif_send(M2M_REQ_GROUP_WIFI, M2M_WIFI_REQ_SET_MAC_MCAST, (uint8 *)&strMulticastMac,sizeof(tstrM2MMulticastMac),NULL,0,0); + } + + return s8ret; + +} + +/*! +@fn \ + NMI_API sint8 m2m_wifi_set_receive_buffer(void* pvBuffer,uint16 u16BufferLen); + +@brief + set the ethernet receive buffer, should be called in the receive call back. + +@param [in] pvBuffer + Pointer to the ethernet receive buffer. +@param [in] u16BufferLen + Length of the buffer. + +@return + The function SHALL return 0 for success and a negative value otherwise. +*/ +NMI_API sint8 m2m_wifi_set_receive_buffer(void* pvBuffer,uint16 u16BufferLen) +{ + sint8 s8ret = M2M_SUCCESS; + if(pvBuffer != NULL) + { + gau8ethRcvBuf = pvBuffer; + gu16ethRcvBufSize= u16BufferLen; + } + else + { + s8ret = M2M_ERR_FAIL; + M2M_ERR("Buffer NULL pointer\r\n"); + } + return s8ret; +} +#endif /* ETH_MODE */ + diff --git a/ext/drivers/atmel/winc1500/driver/source/nmasic.c b/ext/drivers/atmel/winc1500/driver/source/nmasic.c new file mode 100755 index 0000000000000..82b1e4e2bfed1 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmasic.c @@ -0,0 +1,720 @@ +/** + * + * \file + * + * \brief This module contains NMC1500 ASIC specific internal APIs. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "common/include/nm_common.h" +#include "driver/source/nmbus.h" +#include "bsp/include/nm_bsp.h" +#include "driver/source/nmasic.h" +#include "driver/include/m2m_types.h" + +#define NMI_GLB_RESET_0 (NMI_PERIPH_REG_BASE + 0x400) +#define NMI_INTR_REG_BASE (NMI_PERIPH_REG_BASE + 0xa00) +#define NMI_PIN_MUX_0 (NMI_PERIPH_REG_BASE + 0x408) +#define NMI_INTR_ENABLE (NMI_INTR_REG_BASE) +#define GET_UINT32(X,Y) (X[0+Y] + ((uint32)X[1+Y]<<8) + ((uint32)X[2+Y]<<16) +((uint32)X[3+Y]<<24)) + +#define TIMEOUT (0xfffffffful) +#define M2M_DISABLE_PS (0xd0ul) + +static uint32 clk_status_reg_adr = 0xf; /* Assume initially it is B0 chip */ + +sint8 chip_apply_conf(uint32 u32Conf) +{ + sint8 ret = M2M_SUCCESS; + uint32 val32 = u32Conf; + +#ifdef __ENABLE_PMU__ + val32 |= rHAVE_USE_PMU_BIT; +#endif +#ifdef __ENABLE_SLEEP_CLK_SRC_RTC__ + val32 |= rHAVE_SLEEP_CLK_SRC_RTC_BIT; +#elif defined __ENABLE_SLEEP_CLK_SRC_XO__ + val32 |= rHAVE_SLEEP_CLK_SRC_XO_BIT; +#endif +#ifdef __ENABLE_EXT_PA_INV_TX_RX__ + val32 |= rHAVE_EXT_PA_INV_TX_RX; +#endif +#ifdef __ENABLE_LEGACY_RF_SETTINGS__ + val32 |= rHAVE_LEGACY_RF_SETTINGS; +#endif +#ifdef __DISABLE_FIRMWARE_LOGS__ + val32 |= rHAVE_LOGS_DISABLED_BIT; +#endif + do { + nm_write_reg(rNMI_GP_REG_1, val32); + if(val32 != 0) { + uint32 reg = 0; + ret = nm_read_reg_with_ret(rNMI_GP_REG_1, ®); + if(ret == M2M_SUCCESS) { + if(reg == val32) + break; + } + } else { + break; + } + } while(1); + + return M2M_SUCCESS; +} + +/** +* @fn nm_clkless_wake +* @brief Wakeup the chip using clockless registers +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Samer Sarhan +* @date 06 June 2014 +* @version 1.0 +*/ +sint8 nm_clkless_wake(void) +{ + sint8 ret = M2M_SUCCESS; + uint32 reg, clk_status_reg,trials = 0; + /* wait 1ms, spi data read */ + nm_bsp_sleep(1); + ret = nm_read_reg_with_ret(0x1, ®); + if(ret != M2M_SUCCESS) { + M2M_ERR("Bus error (1). Wake up failed\n"); + goto _WAKE_EXIT; + } + /* + * At this point, I am not sure whether it is B0 or A0 + * If B0, then clks_enabled bit exists in register 0xf + * If A0, then clks_enabled bit exists in register 0xe + */ + do + { + /* Set bit 1 */ + nm_write_reg(0x1, reg | (1 << 1)); + /* wait 1ms, spi data read */ + nm_bsp_sleep(1); + // Check the clock status + ret = nm_read_reg_with_ret(clk_status_reg_adr, &clk_status_reg); + if( (ret != M2M_SUCCESS) || ((ret == M2M_SUCCESS) && (clk_status_reg == 0)) ) { + /* Register 0xf did not exist in A0. + * If register 0xf fails to read or if it reads 0, + * then the chip is A0. + */ + clk_status_reg_adr = 0xe; + /* wait 1ms, spi data read */ + nm_bsp_sleep(1); + ret = nm_read_reg_with_ret(clk_status_reg_adr, &clk_status_reg); + + /* Aelmeleh 24-08-2015*/ + /* Check for C3000 rev. D0 value */ + if( (ret != M2M_SUCCESS) || ((ret == M2M_SUCCESS) && (clk_status_reg == 0)) ) { + + clk_status_reg_adr = 0x13; + /* wait 1ms, spi data read */ + nm_bsp_sleep(1); + ret = nm_read_reg_with_ret(clk_status_reg_adr, &clk_status_reg); + + if(ret != M2M_SUCCESS) { + M2M_ERR("Bus error (2). Wake up failed\n"); + goto _WAKE_EXIT; + } + } + } + + // in case of clocks off, wait 2ms, and check it again. + // if still off, wait for another 2ms, for a total wait of 6ms. + // If still off, redo the wake up sequence + while( ((clk_status_reg & 0x4) == 0) && (((++trials) %3) == 0)) + { + /* Wait for the chip to stabilize*/ + nm_bsp_sleep(2); + + // Make sure chip is awake. This is an extra step that can be removed + // later to avoid the bus access overhead + nm_read_reg_with_ret(clk_status_reg_adr, &clk_status_reg); + + if((clk_status_reg & 0x4) == 0) + { + M2M_ERR("clocks still OFF. Wake up failed\n"); + } + } + // in case of failure, Reset the wakeup bit to introduce a new edge on the next loop + if((clk_status_reg & 0x4) == 0) + { + // Reset bit 0 + nm_write_reg(0x1, reg | (1 << 1)); + } + } while((clk_status_reg & 0x4) == 0); + +_WAKE_EXIT: + return ret; +} +void chip_idle(void) +{ + uint32 reg =0; + nm_read_reg_with_ret(0x1, ®); + if(reg&0x2) + { + reg &=~(1 << 1); + nm_write_reg(0x1, reg); + } +} + +void enable_rf_blocks(void) +{ + nm_write_reg(0x6, 0xdb); + nm_write_reg(0x7, 0x6); + nm_bsp_sleep(10); + nm_write_reg(0x1480, 0); + nm_write_reg(0x1484, 0); + nm_bsp_sleep(10); + + nm_write_reg(0x6, 0x0); + nm_write_reg(0x7, 0x0); +} + +sint8 enable_interrupts(void) +{ + uint32 reg; + sint8 ret; + /** + interrupt pin mux select + **/ + ret = nm_read_reg_with_ret(NMI_PIN_MUX_0, ®); + if (M2M_SUCCESS != ret) { + return M2M_ERR_BUS_FAIL; + } + reg |= ((uint32) 1 << 8); + ret = nm_write_reg(NMI_PIN_MUX_0, reg); + if (M2M_SUCCESS != ret) { + return M2M_ERR_BUS_FAIL; + } + /** + interrupt enable + **/ + ret = nm_read_reg_with_ret(NMI_INTR_ENABLE, ®); + if (M2M_SUCCESS != ret) { + return M2M_ERR_BUS_FAIL; + } + reg |= ((uint32) 1 << 16); + ret = nm_write_reg(NMI_INTR_ENABLE, reg); + if (M2M_SUCCESS != ret) { + return M2M_ERR_BUS_FAIL; + } + return M2M_SUCCESS; +} + +sint8 cpu_start(void) { + uint32 reg; + sint8 ret; + + /** + reset regs + */ + nm_write_reg(BOOTROM_REG,0); + nm_write_reg(NMI_STATE_REG,0); + nm_write_reg(NMI_REV_REG,0); + + /** + Go... + **/ + ret = nm_read_reg_with_ret(0x1118, ®); + if (M2M_SUCCESS != ret) { + ret = M2M_ERR_BUS_FAIL; + M2M_ERR("[nmi start]: fail read reg 0x1118 ...\n"); + } + reg |= (1 << 0); + ret = nm_write_reg(0x1118, reg); + ret = nm_write_reg(0x150014, 0x1); + ret += nm_read_reg_with_ret(NMI_GLB_RESET_0, ®); + if ((reg & (1ul << 10)) == (1ul << 10)) { + reg &= ~(1ul << 10); + ret += nm_write_reg(NMI_GLB_RESET_0, reg); + } + + reg |= (1ul << 10); + ret += nm_write_reg(NMI_GLB_RESET_0, reg); + nm_bsp_sleep(1); /* TODO: Why bus error if this delay is not here. */ + return ret; +} + +uint32 nmi_get_chipid(void) +{ + static uint32 chipid = 0; + + if (chipid == 0) { + uint32 rfrevid; + + if((nm_read_reg_with_ret(0x1000, &chipid)) != M2M_SUCCESS) { + chipid = 0; + return 0; + } + //if((ret = nm_read_reg_with_ret(0x11fc, &revid)) != M2M_SUCCESS) { + // return 0; + //} + if((nm_read_reg_with_ret(0x13f4, &rfrevid)) != M2M_SUCCESS) { + chipid = 0; + return 0; + } + + if (chipid == 0x1002a0) { + if (rfrevid == 0x1) { /* 1002A0 */ + } else /* if (rfrevid == 0x2) */ { /* 1002A1 */ + chipid = 0x1002a1; + } + } else if(chipid == 0x1002b0) { + if(rfrevid == 3) { /* 1002B0 */ + } else if(rfrevid == 4) { /* 1002B1 */ + chipid = 0x1002b1; + } else /* if(rfrevid == 5) */ { /* 1002B2 */ + chipid = 0x1002b2; + } + } else if(chipid == 0x1000F0) { + if((nm_read_reg_with_ret(0x3B0000, &chipid)) != M2M_SUCCESS) { + chipid = 0; + return 0; + } + } else { + + } +//#define PROBE_FLASH +#ifdef PROBE_FLASH + if(chipid) { + UWORD32 flashid; + + flashid = probe_spi_flash(); + if(flashid == 0x1230ef) { + chipid &= ~(0x0f0000); + chipid |= 0x050000; + } + if(flashid == 0xc21320c2) { + chipid &= ~(0x0f0000); + chipid |= 0x050000; + } + } +#else + /*M2M is by default have SPI flash*/ + chipid &= ~(0x0f0000); + chipid |= 0x050000; +#endif /* PROBE_FLASH */ + } + return chipid; +} + +uint32 nmi_get_rfrevid(void) +{ + uint32 rfrevid; + if((nm_read_reg_with_ret(0x13f4, &rfrevid)) != M2M_SUCCESS) { + rfrevid = 0; + return 0; + } + return rfrevid; +} + +void restore_pmu_settings_after_global_reset(void) +{ + /* + * Must restore PMU register value after + * global reset if PMU toggle is done at + * least once since the last hard reset. + */ + if(REV(nmi_get_chipid()) >= REV_2B0) { + nm_write_reg(0x1e48, 0xb78469ce); + } +} + +void nmi_update_pll(void) +{ + uint32 pll; + + pll = nm_read_reg(0x1428); + pll &= ~0x1ul; + nm_write_reg(0x1428, pll); + pll |= 0x1ul; + nm_write_reg(0x1428, pll); + +} +void nmi_set_sys_clk_src_to_xo(void) +{ + uint32 val32; + + /* Switch system clock source to XO. This will take effect after nmi_update_pll(). */ + val32 = nm_read_reg(0x141c); + val32 |= (1 << 2); + nm_write_reg(0x141c, val32); + + /* Do PLL update */ + nmi_update_pll(); +} +static uint8 check_3000_id(void) +{ + return ((nmi_get_chipid() & (0xf00000)) == 0x300000); +} + +sint8 chip_wake(void) +{ + sint8 ret = M2M_SUCCESS; + ret = nm_clkless_wake(); + if(ret != M2M_SUCCESS) return ret; + if(!check_3000_id()) + { + enable_rf_blocks(); + } + + + return ret; +} +sint8 chip_reset_and_cpu_halt(void) +{ + sint8 ret = M2M_SUCCESS; + uint32 reg = 0; + + ret = chip_wake(); + if(ret != M2M_SUCCESS) { + return ret; + } + if(!check_3000_id()) + { + chip_reset(); + ret = nm_read_reg_with_ret(0x1118, ®); + if (M2M_SUCCESS != ret) { + ret = M2M_ERR_BUS_FAIL; + M2M_ERR("[nmi start]: fail read reg 0x1118 ...\n"); + } + reg |= (1 << 0); + ret = nm_write_reg(0x1118, reg); + ret += nm_read_reg_with_ret(NMI_GLB_RESET_0, ®); + if ((reg & (1ul << 10)) == (1ul << 10)) { + reg &= ~(1ul << 10); + ret += nm_write_reg(NMI_GLB_RESET_0, reg); + ret += nm_read_reg_with_ret(NMI_GLB_RESET_0, ®); + } + nm_write_reg(BOOTROM_REG,0); + nm_write_reg(NMI_STATE_REG,0); + nm_write_reg(NMI_REV_REG,0); + nm_write_reg(NMI_PIN_MUX_0, 0x11111000); + } + return ret; +} +sint8 chip_reset(void) +{ + sint8 ret = M2M_SUCCESS; +#ifndef CONF_WINC_USE_UART + nmi_set_sys_clk_src_to_xo(); +#endif + ret += nm_write_reg(NMI_GLB_RESET_0, 0); + nm_bsp_sleep(50); +#ifndef CONF_WINC_USE_UART + restore_pmu_settings_after_global_reset(); +#endif + return ret; +} + +sint8 wait_for_bootrom(uint8 arg) +{ + sint8 ret = M2M_SUCCESS; + uint32 reg = 0, cnt = 0; + uint32 u32GpReg1 = 0; + + reg = 0; + while(1) { + reg = nm_read_reg(0x1014); /* wait for efuse loading done */ + if (reg & 0x80000000) { + break; + } + nm_bsp_sleep(1); /* TODO: Why bus error if this delay is not here. */ + } + reg = nm_read_reg(M2M_WAIT_FOR_HOST_REG); + reg &= 0x1; + + /* check if waiting for the host will be skipped or not */ + if(reg == 0) + { + reg = 0; + while(reg != M2M_FINISH_BOOT_ROM) + { + nm_bsp_sleep(1); + reg = nm_read_reg(BOOTROM_REG); + + if(++cnt > TIMEOUT) + { + M2M_DBG("failed to load firmware from flash.\n"); + ret = M2M_ERR_INIT; + goto ERR2; + } + } + } + + if(M2M_WIFI_MODE_ATE_HIGH == arg) { + nm_write_reg(NMI_REV_REG, M2M_ATE_FW_START_VALUE); + nm_write_reg(NMI_STATE_REG, NBIT20); + }else if(M2M_WIFI_MODE_ATE_LOW == arg) { + nm_write_reg(NMI_REV_REG, M2M_ATE_FW_START_VALUE); + nm_write_reg(NMI_STATE_REG, 0); + }else if(M2M_WIFI_MODE_ETHERNET == arg){ + u32GpReg1 = rHAVE_ETHERNET_MODE_BIT; + } else { + /*bypass this step*/ + } + + if(REV(nmi_get_chipid()) == REV_3A0) + { + chip_apply_conf(u32GpReg1 | rHAVE_USE_PMU_BIT); + } + else + { + chip_apply_conf(u32GpReg1); + } + + nm_write_reg(BOOTROM_REG,M2M_START_FIRMWARE); + +#ifdef __ROM_TEST__ + rom_test(); +#endif /* __ROM_TEST__ */ + +ERR2: + return ret; +} + +sint8 wait_for_firmware_start(uint8 arg) +{ + sint8 ret = M2M_SUCCESS; + uint32 reg = 0, cnt = 0; + uint32 u32Timeout = TIMEOUT; + volatile uint32 regAddress = NMI_STATE_REG; + volatile uint32 checkValue = M2M_FINISH_INIT_STATE; + + if((M2M_WIFI_MODE_ATE_HIGH == arg)||(M2M_WIFI_MODE_ATE_LOW == arg)) { + regAddress = NMI_REV_REG; + checkValue = M2M_ATE_FW_IS_UP_VALUE; + } else { + /*bypass this step*/ + } + + + while (checkValue != reg) + { + + nm_bsp_sleep(2); /* TODO: Why bus error if this delay is not here. */ + M2M_DBG("%x %x %x\n",(unsigned int)nm_read_reg(0x108c),(unsigned int)nm_read_reg(0x108c),(unsigned int)nm_read_reg(0x14A0)); + reg = nm_read_reg(regAddress); + if(++cnt >= u32Timeout) + { + M2M_DBG("Time out for wait firmware Run\n"); + ret = M2M_ERR_INIT; + goto ERR; + } + } + if(M2M_FINISH_INIT_STATE == checkValue) + { + nm_write_reg(NMI_STATE_REG, 0); + } +ERR: + return ret; +} + +sint8 chip_deinit(void) +{ + uint32 reg = 0; + sint8 ret; + uint8 timeout = 10; + + /** + stop the firmware, need a re-download + **/ + ret = nm_read_reg_with_ret(NMI_GLB_RESET_0, ®); + if (ret != M2M_SUCCESS) { + M2M_ERR("failed to de-initialize\n"); + } + reg &= ~(1 << 10); + ret = nm_write_reg(NMI_GLB_RESET_0, reg); + + if (ret != M2M_SUCCESS) { + M2M_ERR("Error while writing reg\n"); + return ret; + } + + do { + ret = nm_read_reg_with_ret(NMI_GLB_RESET_0, ®); + if (ret != M2M_SUCCESS) { + M2M_ERR("Error while reading reg\n"); + return ret; + } + /*Workaround to ensure that the chip is actually reset*/ + if ((reg & (1 << 10))) { + M2M_DBG("Bit 10 not reset retry %d\n", timeout); + reg &= ~(1 << 10); + ret = nm_write_reg(NMI_GLB_RESET_0, reg); + timeout--; + } else { + break; + } + + } while (timeout); + + return ret; +} + +sint8 set_gpio_dir(uint8 gpio, uint8 dir) +{ + uint32 val32; + sint8 ret; + + ret = nm_read_reg_with_ret(0x20108, &val32); + if(ret != M2M_SUCCESS) goto _EXIT; + + if(dir) { + val32 |= (1ul << gpio); + } else { + val32 &= ~(1ul << gpio); + } + + ret = nm_write_reg(0x20108, val32); + +_EXIT: + return ret; +} +sint8 set_gpio_val(uint8 gpio, uint8 val) +{ + uint32 val32; + sint8 ret; + + ret = nm_read_reg_with_ret(0x20100, &val32); + if(ret != M2M_SUCCESS) goto _EXIT; + + if(val) { + val32 |= (1ul << gpio); + } else { + val32 &= ~(1ul << gpio); + } + + ret = nm_write_reg(0x20100, val32); + +_EXIT: + return ret; +} + +sint8 get_gpio_val(uint8 gpio, uint8* val) +{ + uint32 val32; + sint8 ret; + + ret = nm_read_reg_with_ret(0x20104, &val32); + if(ret != M2M_SUCCESS) goto _EXIT; + + *val = (uint8)((val32 >> gpio) & 0x01); + +_EXIT: + return ret; +} + +sint8 pullup_ctrl(uint32 pinmask, uint8 enable) +{ + sint8 s8Ret; + uint32 val32; + s8Ret = nm_read_reg_with_ret(0x142c, &val32); + if(s8Ret != M2M_SUCCESS) { + M2M_ERR("[pullup_ctrl]: failed to read\n"); + goto _EXIT; + } + if(enable) { + val32 &= ~pinmask; + } else { + val32 |= pinmask; + } + s8Ret = nm_write_reg(0x142c, val32); + if(s8Ret != M2M_SUCCESS) { + M2M_ERR("[pullup_ctrl]: failed to write\n"); + goto _EXIT; + } +_EXIT: + return s8Ret; +} + +sint8 nmi_get_otp_mac_address(uint8 *pu8MacAddr, uint8 * pu8IsValid) +{ + sint8 ret; + uint32 u32RegValue; + uint8 mac[6]; + tstrGpRegs strgp = {0}; + + ret = nm_read_reg_with_ret(rNMI_GP_REG_2, &u32RegValue); + if(ret != M2M_SUCCESS) goto _EXIT_ERR; + + ret = nm_read_block(u32RegValue|0x30000,(uint8*)&strgp,sizeof(tstrGpRegs)); + if(ret != M2M_SUCCESS) goto _EXIT_ERR; + u32RegValue = strgp.u32Mac_efuse_mib; + + if(!EFUSED_MAC(u32RegValue)) { + M2M_DBG("Default MAC\n"); + m2m_memset(pu8MacAddr, 0, 6); + goto _EXIT_ERR; + } + + M2M_DBG("OTP MAC\n"); + u32RegValue >>=16; + ret = nm_read_block(u32RegValue|0x30000, mac, 6); + m2m_memcpy(pu8MacAddr,mac,6); + if(pu8IsValid) *pu8IsValid = 1; + return ret; + +_EXIT_ERR: + if(pu8IsValid) *pu8IsValid = 0; + return ret; +} + +sint8 nmi_get_mac_address(uint8 *pu8MacAddr) +{ + sint8 ret; + uint32 u32RegValue; + uint8 mac[6]; + tstrGpRegs strgp = {0}; + + ret = nm_read_reg_with_ret(rNMI_GP_REG_2, &u32RegValue); + if(ret != M2M_SUCCESS) goto _EXIT_ERR; + + ret = nm_read_block(u32RegValue|0x30000,(uint8*)&strgp,sizeof(tstrGpRegs)); + if(ret != M2M_SUCCESS) goto _EXIT_ERR; + u32RegValue = strgp.u32Mac_efuse_mib; + + u32RegValue &=0x0000ffff; + ret = nm_read_block(u32RegValue|0x30000, mac, 6); + m2m_memcpy(pu8MacAddr, mac, 6); + + return ret; + +_EXIT_ERR: + return ret; +} \ No newline at end of file diff --git a/ext/drivers/atmel/winc1500/driver/source/nmasic.h b/ext/drivers/atmel/winc1500/driver/source/nmasic.h new file mode 100755 index 0000000000000..ff3805ba10521 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmasic.h @@ -0,0 +1,148 @@ +/** + * + * \file + * + * \brief This module contains NMC1500 ASIC specific internal APIs. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +#ifndef _NMASIC_H_ +#define _NMASIC_H_ + +#include "common/include/nm_common.h" + +#define NMI_PERIPH_REG_BASE 0x1000 +#define NMI_CHIPID (NMI_PERIPH_REG_BASE) +#define rNMI_GP_REG_0 (0x149c) +#define rNMI_GP_REG_1 (0x14A0) +#define rNMI_GP_REG_2 (0xc0008) +#define rNMI_GLB_RESET (0x1400) +#define rNMI_BOOT_RESET_MUX (0x1118) +#define NMI_STATE_REG (0x108c) +#define BOOTROM_REG (0xc000c) +#define NMI_REV_REG (0x207ac) /*Also, Used to load ATE firmware from SPI Flash and to ensure that it is running too*/ +#define NMI_REV_REG_ATE (0x1048) /*Revision info register in case of ATE FW*/ +#define M2M_WAIT_FOR_HOST_REG (0x207bc) +#define M2M_FINISH_INIT_STATE 0x02532636UL +#define M2M_FINISH_BOOT_ROM 0x10add09eUL +#define M2M_START_FIRMWARE 0xef522f61UL +#define M2M_START_PS_FIRMWARE 0x94992610UL + +#define M2M_ATE_FW_START_VALUE (0x3C1CD57D) /*Also, Change this value in boot_firmware if it will be changed here*/ +#define M2M_ATE_FW_IS_UP_VALUE (0xD75DC1C3) /*Also, Change this value in ATE (Burst) firmware if it will be changed here*/ + +#define REV_2B0 (0x2B0) +#define REV_B0 (0x2B0) +#define REV_3A0 (0x3A0) +#define GET_CHIPID() nmi_get_chipid() +#define ISNMC1000(id) (((id & 0xfffff000) == 0x100000) ? 1 : 0) +#define ISNMC1500(id) (((id & 0xfffff000) == 0x150000) ? 1 : 0) +#define REV(id) ( ((id) & 0x00000fff ) ) +#define EFUSED_MAC(value) (value & 0xffff0000) + +#define rHAVE_SDIO_IRQ_GPIO_BIT (NBIT0) +#define rHAVE_USE_PMU_BIT (NBIT1) +#define rHAVE_SLEEP_CLK_SRC_RTC_BIT (NBIT2) +#define rHAVE_SLEEP_CLK_SRC_XO_BIT (NBIT3) +#define rHAVE_EXT_PA_INV_TX_RX (NBIT4) +#define rHAVE_LEGACY_RF_SETTINGS (NBIT5) +#define rHAVE_LOGS_DISABLED_BIT (NBIT6) +#define rHAVE_ETHERNET_MODE_BIT (NBIT7) + +typedef struct{ + uint32 u32Mac_efuse_mib; + uint32 u32Firmware_Ota_rev; +}tstrGpRegs; + +#ifdef __cplusplus + extern "C" { + #endif +/** +* @fn nm_clkless_wake +* @brief Wakeup the chip using clockless registers +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Samer Sarhan +*/ +sint8 nm_clkless_wake(void); + +sint8 chip_wake(void); + +void chip_idle(void); + +void enable_rf_blocks(void); + +sint8 enable_interrupts(void); + +sint8 cpu_start(void); + +uint32 nmi_get_chipid(void); + +uint32 nmi_get_rfrevid(void); + +void restore_pmu_settings_after_global_reset(void); + +void nmi_update_pll(void); + +void nmi_set_sys_clk_src_to_xo(void); + +sint8 chip_reset(void); + +sint8 wait_for_bootrom(uint8); + +sint8 wait_for_firmware_start(uint8); + +sint8 chip_deinit(void); + +sint8 chip_reset_and_cpu_halt(void); + +sint8 set_gpio_dir(uint8 gpio, uint8 dir); + +sint8 set_gpio_val(uint8 gpio, uint8 val); + +sint8 get_gpio_val(uint8 gpio, uint8* val); + +sint8 pullup_ctrl(uint32 pinmask, uint8 enable); + +sint8 nmi_get_otp_mac_address(uint8 *pu8MacAddr, uint8 * pu8IsValid); + +sint8 nmi_get_mac_address(uint8 *pu8MacAddr); + +sint8 chip_apply_conf(uint32 u32conf); + +#ifdef __cplusplus + } + #endif + +#endif /*_NMASIC_H_*/ diff --git a/ext/drivers/atmel/winc1500/driver/source/nmbus.c b/ext/drivers/atmel/winc1500/driver/source/nmbus.c new file mode 100755 index 0000000000000..88354437d0533 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmbus.c @@ -0,0 +1,279 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +#ifndef CORTUS_APP + +#include "nmbus.h" +#include "nmi2c.h" +#include "nmspi.h" +#include "nmuart.h" + +#define MAX_TRX_CFG_SZ 8 + +/** +* @fn nm_bus_iface_init +* @brief Initialize bus interface +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_bus_iface_init(void *pvInitVal) +{ + sint8 ret = M2M_SUCCESS; + ret = nm_bus_init(pvInitVal); + + return ret; +} + +/** +* @fn nm_bus_iface_deinit +* @brief Deinitialize bus interface +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Samer Sarhan +* @date 07 April 2014 +* @version 1.0 +*/ +sint8 nm_bus_iface_deinit(void) +{ + sint8 ret = M2M_SUCCESS; + ret = nm_bus_deinit(); + + return ret; +} + +/** +* @fn nm_bus_iface_reconfigure +* @brief reconfigure bus interface +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Viswanathan Murugesan +* @date 22 Oct 2014 +* @version 1.0 +*/ +sint8 nm_bus_iface_reconfigure(void *ptr) +{ + sint8 ret = M2M_SUCCESS; +#ifdef CONF_WINC_USE_UART + ret = nm_uart_reconfigure(ptr); +#endif + return ret; +} +/* +* @fn nm_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +uint32 nm_read_reg(uint32 u32Addr) +{ +#ifdef CONF_WINC_USE_UART + return nm_uart_read_reg(u32Addr); +#elif defined (CONF_WINC_USE_SPI) + return nm_spi_read_reg(u32Addr); +#elif defined (CONF_WINC_USE_I2C) + return nm_i2c_read_reg(u32Addr); +#else +#error "Plesae define bus usage" +#endif + +} + +/* +* @fn nm_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal) +{ +#ifdef CONF_WINC_USE_UART + return nm_uart_read_reg_with_ret(u32Addr,pu32RetVal); +#elif defined (CONF_WINC_USE_SPI) + return nm_spi_read_reg_with_ret(u32Addr,pu32RetVal); +#elif defined (CONF_WINC_USE_I2C) + return nm_i2c_read_reg_with_ret(u32Addr,pu32RetVal); +#else +#error "Plesae define bus usage" +#endif +} + +/* +* @fn nm_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_write_reg(uint32 u32Addr, uint32 u32Val) +{ +#ifdef CONF_WINC_USE_UART + return nm_uart_write_reg(u32Addr,u32Val); +#elif defined (CONF_WINC_USE_SPI) + return nm_spi_write_reg(u32Addr,u32Val); +#elif defined (CONF_WINC_USE_I2C) + return nm_i2c_write_reg(u32Addr,u32Val); +#else +#error "Plesae define bus usage" +#endif +} + +static sint8 p_nm_read_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz) +{ +#ifdef CONF_WINC_USE_UART + return nm_uart_read_block(u32Addr,puBuf,u16Sz); +#elif defined (CONF_WINC_USE_SPI) + return nm_spi_read_block(u32Addr,puBuf,u16Sz); +#elif defined (CONF_WINC_USE_I2C) + return nm_i2c_read_block(u32Addr,puBuf,u16Sz); +#else +#error "Plesae define bus usage" +#endif + +} +/* +* @fn nm_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u32Sz +* Number of bytes to read. The buffer size must be >= u32Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_read_block(uint32 u32Addr, uint8 *puBuf, uint32 u32Sz) +{ + uint16 u16MaxTrxSz = nm_bus_capabilities.max_trx_size - MAX_TRX_CFG_SZ; + uint32 off = 0; + sint8 s8Ret = M2M_SUCCESS; + + for(;;) + { + if(u32Sz <= u16MaxTrxSz) + { + s8Ret += p_nm_read_block(u32Addr, &puBuf[off], (uint16)u32Sz); + break; + } + else + { + s8Ret += p_nm_read_block(u32Addr, &puBuf[off], u16MaxTrxSz); + if(M2M_SUCCESS != s8Ret) break; + u32Sz -= u16MaxTrxSz; + off += u16MaxTrxSz; + u32Addr += u16MaxTrxSz; + } + } + + return s8Ret; +} + +static sint8 p_nm_write_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz) +{ +#ifdef CONF_WINC_USE_UART + return nm_uart_write_block(u32Addr,puBuf,u16Sz); +#elif defined (CONF_WINC_USE_SPI) + return nm_spi_write_block(u32Addr,puBuf,u16Sz); +#elif defined (CONF_WINC_USE_I2C) + return nm_i2c_write_block(u32Addr,puBuf,u16Sz); +#else +#error "Plesae define bus usage" +#endif + +} +/** +* @fn nm_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u32Sz +* Number of bytes to write. The buffer size must be >= u32Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_write_block(uint32 u32Addr, uint8 *puBuf, uint32 u32Sz) +{ + uint16 u16MaxTrxSz = nm_bus_capabilities.max_trx_size - MAX_TRX_CFG_SZ; + uint32 off = 0; + sint8 s8Ret = M2M_SUCCESS; + + for(;;) + { + if(u32Sz <= u16MaxTrxSz) + { + s8Ret += p_nm_write_block(u32Addr, &puBuf[off], (uint16)u32Sz); + break; + } + else + { + s8Ret += p_nm_write_block(u32Addr, &puBuf[off], u16MaxTrxSz); + if(M2M_SUCCESS != s8Ret) break; + u32Sz -= u16MaxTrxSz; + off += u16MaxTrxSz; + u32Addr += u16MaxTrxSz; + } + } + + return s8Ret; +} + +#endif + diff --git a/ext/drivers/atmel/winc1500/driver/source/nmbus.h b/ext/drivers/atmel/winc1500/driver/source/nmbus.h new file mode 100755 index 0000000000000..06b1a1dba2511 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmbus.h @@ -0,0 +1,139 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NMBUS_H_ +#define _NMBUS_H_ + +#include "common/include/nm_common.h" +#include "bus_wrapper/include/nm_bus_wrapper.h" + + + +#ifdef __cplusplus +extern "C"{ +#endif +/** +* @fn nm_bus_iface_init +* @brief Initialize bus interface +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_bus_iface_init(void *); + + +/** +* @fn nm_bus_iface_deinit +* @brief Deinitialize bus interface +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_bus_iface_deinit(void); + +/** +* @fn nm_bus_iface_reconfigure +* @brief reconfigure bus interface +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_bus_iface_reconfigure(void *ptr); + +/** +* @fn nm_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +*/ +uint32 nm_read_reg(uint32 u32Addr); + +/** +* @fn nm_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal); + +/** +* @fn nm_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_write_reg(uint32 u32Addr, uint32 u32Val); + +/** +* @fn nm_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u32Sz +* Number of bytes to read. The buffer size must be >= u32Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_read_block(uint32 u32Addr, uint8 *puBuf, uint32 u32Sz); + +/** +* @fn nm_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u32Sz +* Number of bytes to write. The buffer size must be >= u32Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_write_block(uint32 u32Addr, uint8 *puBuf, uint32 u32Sz); + + + + +#ifdef __cplusplus +} +#endif + +#endif /* _NMBUS_H_ */ diff --git a/ext/drivers/atmel/winc1500/driver/source/nmdrv.c b/ext/drivers/atmel/winc1500/driver/source/nmdrv.c new file mode 100755 index 0000000000000..9344515018359 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmdrv.c @@ -0,0 +1,397 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 M2M driver APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "common/include/nm_common.h" +#include "driver/source/nmbus.h" +#include "bsp/include/nm_bsp.h" +#include "driver/source/nmdrv.h" +#include "driver/source/nmasic.h" +#include "driver/include/m2m_types.h" +#include "spi_flash/include/spi_flash.h" + +#ifdef CONF_WINC_USE_SPI +#include "driver/source/nmspi.h" +#endif + +/** +* @fn nm_get_firmware_info(tstrM2mRev* M2mRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters +* @version 1.0 +*/ +sint8 nm_get_firmware_info(tstrM2mRev* M2mRev) +{ + uint16 curr_drv_ver, min_req_drv_ver,curr_firm_ver; + uint32 reg = 0; + sint8 ret = M2M_SUCCESS; + + ret = nm_read_reg_with_ret(NMI_REV_REG, ®); + //In case the Firmware running is ATE fw + if(M2M_ATE_FW_IS_UP_VALUE == reg) + { + //Read FW info again from the register specified for ATE + ret = nm_read_reg_with_ret(NMI_REV_REG_ATE, ®); + } + M2mRev->u8DriverMajor = M2M_GET_DRV_MAJOR(reg); + M2mRev->u8DriverMinor = M2M_GET_DRV_MINOR(reg); + M2mRev->u8DriverPatch = M2M_GET_DRV_PATCH(reg); + M2mRev->u8FirmwareMajor = M2M_GET_FW_MAJOR(reg); + M2mRev->u8FirmwareMinor = M2M_GET_FW_MINOR(reg); + M2mRev->u8FirmwarePatch = M2M_GET_FW_PATCH(reg); + M2mRev->u32Chipid = nmi_get_chipid(); + + curr_firm_ver = M2M_MAKE_VERSION(M2mRev->u8FirmwareMajor, M2mRev->u8FirmwareMinor,M2mRev->u8FirmwarePatch); + curr_drv_ver = M2M_MAKE_VERSION(M2M_DRIVER_VERSION_MAJOR_NO, M2M_DRIVER_VERSION_MINOR_NO, M2M_DRIVER_VERSION_PATCH_NO); + min_req_drv_ver = M2M_MAKE_VERSION(M2mRev->u8DriverMajor, M2mRev->u8DriverMinor,M2mRev->u8DriverPatch); + if(curr_drv_ver < min_req_drv_ver) { + /*The current driver version should be larger or equal + than the min driver that the current firmware support */ + ret = M2M_ERR_FW_VER_MISMATCH; + } + if(curr_drv_ver > curr_firm_ver) { + /*The current driver should be equal or less than the firmware version*/ + ret = M2M_ERR_FW_VER_MISMATCH; + } + return ret; +} +/** +* @fn nm_get_firmware_info(tstrM2mRev* M2mRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters +* @version 1.0 +*/ +sint8 nm_get_firmware_full_info(tstrM2mRev* pstrRev) +{ + uint16 curr_drv_ver, min_req_drv_ver,curr_firm_ver; + uint32 reg = 0; + sint8 ret = M2M_SUCCESS; + tstrGpRegs strgp = {0}; + if (pstrRev != NULL) + { + m2m_memset((uint8*)pstrRev,0,sizeof(tstrM2mRev)); + ret = nm_read_reg_with_ret(rNMI_GP_REG_2, ®); + if(ret == M2M_SUCCESS) + { + if(reg != 0) + { + ret = nm_read_block(reg|0x30000,(uint8*)&strgp,sizeof(tstrGpRegs)); + if(ret == M2M_SUCCESS) + { + reg = strgp.u32Firmware_Ota_rev; + reg &= 0x0000ffff; + if(reg != 0) + { + ret = nm_read_block(reg|0x30000,(uint8*)pstrRev,sizeof(tstrM2mRev)); + if(ret == M2M_SUCCESS) + { + curr_firm_ver = M2M_MAKE_VERSION(pstrRev->u8FirmwareMajor, pstrRev->u8FirmwareMinor,pstrRev->u8FirmwarePatch); + curr_drv_ver = M2M_MAKE_VERSION(M2M_DRIVER_VERSION_MAJOR_NO, M2M_DRIVER_VERSION_MINOR_NO, M2M_DRIVER_VERSION_PATCH_NO); + min_req_drv_ver = M2M_MAKE_VERSION(pstrRev->u8DriverMajor, pstrRev->u8DriverMinor,pstrRev->u8DriverPatch); + if((curr_firm_ver == 0)||(min_req_drv_ver == 0)||(min_req_drv_ver == 0)){ + ret = M2M_ERR_FAIL; + goto EXIT; + } + if(curr_drv_ver < min_req_drv_ver) { + /*The current driver version should be larger or equal + than the min driver that the current firmware support */ + ret = M2M_ERR_FW_VER_MISMATCH; + goto EXIT; + } + if(curr_drv_ver > curr_firm_ver) { + /*The current driver should be equal or less than the firmware version*/ + ret = M2M_ERR_FW_VER_MISMATCH; + goto EXIT; + } + } + }else { + ret = M2M_ERR_FAIL; + } + } + }else{ + ret = M2M_ERR_FAIL; + } + } + } +EXIT: + return ret; +} +/** +* @fn nm_get_ota_firmware_info(tstrM2mRev* pstrRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters + +* @version 1.0 +*/ +sint8 nm_get_ota_firmware_info(tstrM2mRev* pstrRev) +{ + uint16 curr_drv_ver, min_req_drv_ver,curr_firm_ver; + uint32 reg = 0; + sint8 ret; + tstrGpRegs strgp = {0}; + + if (pstrRev != NULL) + { + m2m_memset((uint8*)pstrRev,0,sizeof(tstrM2mRev)); + ret = nm_read_reg_with_ret(rNMI_GP_REG_2, ®); + if(ret == M2M_SUCCESS) + { + if(reg != 0) + { + ret = nm_read_block(reg|0x30000,(uint8*)&strgp,sizeof(tstrGpRegs)); + if(ret == M2M_SUCCESS) + { + reg = strgp.u32Firmware_Ota_rev; + reg >>= 16; + if(reg != 0) + { + ret = nm_read_block(reg|0x30000,(uint8*)pstrRev,sizeof(tstrM2mRev)); + if(ret == M2M_SUCCESS) + { + curr_firm_ver = M2M_MAKE_VERSION(pstrRev->u8FirmwareMajor, pstrRev->u8FirmwareMinor,pstrRev->u8FirmwarePatch); + curr_drv_ver = M2M_MAKE_VERSION(M2M_DRIVER_VERSION_MAJOR_NO, M2M_DRIVER_VERSION_MINOR_NO, M2M_DRIVER_VERSION_PATCH_NO); + min_req_drv_ver = M2M_MAKE_VERSION(pstrRev->u8DriverMajor, pstrRev->u8DriverMinor,pstrRev->u8DriverPatch); + if((curr_firm_ver == 0)||(min_req_drv_ver == 0)||(min_req_drv_ver == 0)){ + ret = M2M_ERR_FAIL; + goto EXIT; + } + if(curr_drv_ver < min_req_drv_ver) { + /*The current driver version should be larger or equal + than the min driver that the current firmware support */ + ret = M2M_ERR_FW_VER_MISMATCH; + } + if(curr_drv_ver > curr_firm_ver) { + /*The current driver should be equal or less than the firmware version*/ + ret = M2M_ERR_FW_VER_MISMATCH; + } + } + }else{ + ret = M2M_ERR_FAIL; + } + } + }else{ + ret = M2M_ERR_FAIL; + } + } + } else { + ret = M2M_ERR_INVALID_ARG; + } +EXIT: + return ret; +} + + + +/* +* @fn nm_drv_init_download_mode +* @brief Initialize NMC1000 driver +* @return M2M_SUCCESS in case of success and Negative error code in case of failure +* @param [in] arg +* Generic argument +* @author Viswanathan Murugesan +* @date 10 Oct 2014 +* @version 1.0 +*/ +sint8 nm_drv_init_download_mode() +{ + sint8 ret = M2M_SUCCESS; + + ret = nm_bus_iface_init(NULL); + if (M2M_SUCCESS != ret) { + M2M_ERR("[nmi start]: fail init bus\n"); + goto ERR1; + } + + /** + reset the chip and halt the cpu in case of no wait efuse is set. + */ + chip_reset_and_cpu_halt(); + + + +#ifdef CONF_WINC_USE_SPI + /* Must do this after global reset to set SPI data packet size. */ + nm_spi_init(); +#endif + + M2M_INFO("Chip ID %lx\n", nmi_get_chipid()); + + /*disable all interrupt in ROM (to disable uart) in 2b0 chip*/ + nm_write_reg(0x20300,0); + +ERR1: + return ret; +} + +/* +* @fn nm_drv_init +* @brief Initialize NMC1000 driver +* @return M2M_SUCCESS in case of success and Negative error code in case of failure +* @param [in] arg +* Generic argument +* @author M. Abdelmawla +* @date 15 July 2012 +* @version 1.0 +*/ +sint8 nm_drv_init(void * arg) +{ + sint8 ret = M2M_SUCCESS; + uint8 u8Mode; + + if(NULL != arg) { + u8Mode = *((uint8 *)arg); + if((u8Mode < M2M_WIFI_MODE_NORMAL)||(u8Mode >= M2M_WIFI_MODE_MAX)) { + u8Mode = M2M_WIFI_MODE_NORMAL; + } + } else { + u8Mode = M2M_WIFI_MODE_NORMAL; + } + + ret = nm_bus_iface_init(NULL); + if (M2M_SUCCESS != ret) { + M2M_ERR("[nmi start]: fail init bus\n"); + goto ERR1; + } + +#ifdef BUS_ONLY + return; +#endif + + +#ifdef NO_HW_CHIP_EN + ret = chip_wake(); + nm_bsp_sleep(10); + if (M2M_SUCCESS != ret) { + M2M_ERR("[nmi start]: fail chip_wakeup\n"); + goto ERR2; + } + /** + Go... + **/ + ret = chip_reset(); + if (M2M_SUCCESS != ret) { + goto ERR2; + } +#endif + M2M_INFO("Chip ID %lx\n", nmi_get_chipid()); +#ifdef CONF_WINC_USE_SPI + /* Must do this after global reset to set SPI data packet size. */ + nm_spi_init(); +#endif +#ifdef NO_HW_CHIP_EN + /*return power save to default value*/ + chip_idle(); + + ret = cpu_start(); + if (M2M_SUCCESS != ret) { + goto ERR2; + } +#endif + ret = wait_for_bootrom(u8Mode); + if (M2M_SUCCESS != ret) { + goto ERR2; + } + + ret = wait_for_firmware_start(u8Mode); + if (M2M_SUCCESS != ret) { + goto ERR2; + } + + if((M2M_WIFI_MODE_ATE_HIGH == u8Mode)||(M2M_WIFI_MODE_ATE_LOW == u8Mode)) { + goto ERR1; + } else { + /*continue running*/ + } + + ret = enable_interrupts(); + if (M2M_SUCCESS != ret) { + M2M_ERR("failed to enable interrupts..\n"); + goto ERR2; + } + + return ret; +ERR2: + nm_bus_iface_deinit(); +ERR1: + return ret; +} + +/* +* @fn nm_drv_deinit +* @brief Deinitialize NMC1000 driver +* @author M. Abdelmawla +* @date 17 July 2012 +* @version 1.0 +*/ +sint8 nm_drv_deinit(void * arg) +{ + sint8 ret; + + ret = chip_deinit(); + if (M2M_SUCCESS != ret) { + M2M_ERR("[nmi stop]: chip_deinit fail\n"); + goto ERR1; + } + + /* Disable SPI flash to save power when the chip is off */ + ret = spi_flash_enable(0); + if (M2M_SUCCESS != ret) { + M2M_ERR("[nmi stop]: SPI flash disable fail\n"); + goto ERR1; + } + + ret = nm_bus_iface_deinit(); + if (M2M_SUCCESS != ret) { + M2M_ERR("[nmi stop]: fail init bus\n"); + goto ERR1; + } +#ifdef CONF_WINC_USE_SPI + /* Must do this after global reset to set SPI data packet size. */ + nm_spi_deinit(); +#endif + +ERR1: + return ret; +} + + diff --git a/ext/drivers/atmel/winc1500/driver/source/nmdrv.h b/ext/drivers/atmel/winc1500/driver/source/nmdrv.h new file mode 100755 index 0000000000000..2ce8ed1c8bf06 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmdrv.h @@ -0,0 +1,126 @@ +/** + * + * \file + * + * \brief This module contains NMC1500 M2M driver APIs declarations. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NMDRV_H_ +#define _NMDRV_H_ + +#include "common/include/nm_common.h" + +/** +* @struct tstrM2mRev +* @brief Structure holding firmware version parameters and build date/time +*/ +typedef struct { + uint32 u32Chipid; /* HW revision which will be basically the chip ID */ + uint8 u8FirmwareMajor; /* Version Major Number which represents the official release base */ + uint8 u8FirmwareMinor; /* Version Minor Number which represents the engineering release base */ + uint8 u8FirmwarePatch; /* Version pathc Number which represents the pathces release base */ + uint8 u8DriverMajor; /* Version Major Number which represents the official release base */ + uint8 u8DriverMinor; /* Version Minor Number which represents the engineering release base */ + uint8 u8DriverPatch; /* Version Patch Number which represents the pathces release base */ + uint8 BuildDate[sizeof(__DATE__)]; + uint8 BuildTime[sizeof(__TIME__)]; + uint8 _PAD8_; +} tstrM2mRev; + +#ifdef __cplusplus + extern "C" { + #endif +/** +* @fn nm_get_firmware_info(tstrM2mRev* M2mRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters +* @version 1.0 +*/ +sint8 nm_get_firmware_info(tstrM2mRev* M2mRev); +/** +* @fn nm_get_firmware_full_info(tstrM2mRev* pstrRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters +* @version 1.0 +*/ +sint8 nm_get_firmware_full_info(tstrM2mRev* pstrRev); +/** +* @fn nm_get_ota_firmware_info(tstrM2mRev* pstrRev) +* @brief Get Firmware version info +* @param [out] M2mRev +* pointer holds address of structure "tstrM2mRev" that contains the firmware version parameters + +* @version 1.0 +*/ +sint8 nm_get_ota_firmware_info(tstrM2mRev* pstrRev); +/* +* @fn nm_drv_init +* @brief Initialize NMC1000 driver +* @return ZERO in case of success and Negative error code in case of failure +*/ +sint8 nm_drv_init_download_mode(void); + +/* +* @fn nm_drv_init +* @brief Initialize NMC1000 driver +* @return M2M_SUCCESS in case of success and Negative error code in case of failure +* @param [in] arg +* Generic argument TBD +* @return ZERO in case of success and Negative error code in case of failure + +*/ +sint8 nm_drv_init(void * arg); + +/** +* @fn nm_drv_deinit +* @brief Deinitialize NMC1000 driver +* @author M. Abdelmawla +* @param [in] arg +* Generic argument TBD +* @return ZERO in case of success and Negative error code in case of failure +*/ +sint8 nm_drv_deinit(void * arg); + +#ifdef __cplusplus + } + #endif + +#endif /*_NMDRV_H_*/ + + diff --git a/ext/drivers/atmel/winc1500/driver/source/nmi2c.c b/ext/drivers/atmel/winc1500/driver/source/nmi2c.c new file mode 100755 index 0000000000000..e11d2f795c15c --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmi2c.c @@ -0,0 +1,269 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 I2C protocol bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "common/include/nm_common.h" + +#ifdef CONF_WINC_USE_I2C + +#include "nmi2c.h" +#include "bus_wrapper/include/nm_bus_wrapper.h" + + +/* +* @fn nm_i2c_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ + sint8 nm_i2c_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal) +{ + uint8 b[6]; + uint8 rsz; + tstrNmI2cDefault strI2c; + sint8 s8Ret = M2M_SUCCESS; + + if(u32Addr < 0xff) { /* clockless i2c */ + b[0] = 0x09; + b[1] = (uint8)(u32Addr); + rsz = 1; + strI2c.u16Sz = 2; + } else { + b[0] = 0x80; + b[1] = (uint8)(u32Addr >> 24); + b[2] = (uint8)(u32Addr >> 16); + b[3] = (uint8)(u32Addr >> 8); + b[4] = (uint8)(u32Addr); + b[5] = 0x04; + rsz = 4; + strI2c.u16Sz = 6; + } + + strI2c.pu8Buf = b; + + if(M2M_SUCCESS == nm_bus_ioctl(NM_BUS_IOCTL_W, &strI2c)) + { + strI2c.u16Sz = rsz; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strI2c)) + { + //M2M_ERR("read error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + M2M_ERR("failed to send cfg bytes\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + + if (rsz == 1) { + *pu32RetVal = b[0]; + } else { + *pu32RetVal = b[0] | ((uint32)b[1] << 8) | ((uint32)b[2] << 16) | ((uint32)b[3] << 24); + } + return s8Ret; +} + +/* +* @fn nm_i2c_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +uint32 nm_i2c_read_reg(uint32 u32Addr) +{ + uint32 val; + nm_i2c_read_reg_with_ret(u32Addr, &val); + return val; +} + +/* +* @fn nm_i2c_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_i2c_write_reg(uint32 u32Addr, uint32 u32Val) +{ + tstrNmI2cDefault strI2c; + uint8 b[16]; + sint8 s8Ret = M2M_SUCCESS; + + if(u32Addr < 0xff) { /* clockless i2c */ + b[0] = 0x19; + b[1] = (uint8)(u32Addr); + b[2] = (uint8)(u32Val); + strI2c.u16Sz = 3; + } else { + b[0] = 0x90; + b[1] = (uint8)(u32Addr >> 24); + b[2] = (uint8)(u32Addr >> 16); + b[3] = (uint8)(u32Addr >> 8); + b[4] = (uint8)u32Addr; + b[5] = 0x04; + b[6] = (uint8)u32Val; + b[7] = (uint8)(u32Val >> 8); + b[8] = (uint8)(u32Val >> 16); + b[9] = (uint8)(u32Val >> 24); + strI2c.u16Sz = 10; + } + + strI2c.pu8Buf = b; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strI2c)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + + return s8Ret; +} + +/* +* @fn nm_i2c_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u16Sz +* Number of bytes to read. The buffer size must be >= u16Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_i2c_read_block(uint32 u32Addr, uint8 *pu8Buf, uint16 u16Sz) +{ + tstrNmI2cDefault strI2c; + uint8 au8Buf[7]; + sint8 s8Ret = M2M_SUCCESS; + + au8Buf[0] = 0x02; + au8Buf[1] = (uint8)(u32Addr >> 24); + au8Buf[2] = (uint8)(u32Addr >> 16); + au8Buf[3] = (uint8)(u32Addr >> 8); + au8Buf[4] = (uint8)(u32Addr >> 0); + au8Buf[5] = (uint8)(u16Sz >> 8); + au8Buf[6] = (uint8)(u16Sz); + + strI2c.pu8Buf = au8Buf; + strI2c.u16Sz = sizeof(au8Buf); + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strI2c)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + else + { + strI2c.pu8Buf = pu8Buf; + strI2c.u16Sz = u16Sz; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strI2c)) + { + M2M_ERR("read error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + + return s8Ret; +} + +/* +* @fn nm_i2c_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u16Sz +* Number of bytes to write. The buffer size must be >= u16Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_i2c_write_block(uint32 u32Addr, uint8 *pu8Buf, uint16 u16Sz) +{ + uint8 au8Buf[7]; + tstrNmI2cSpecial strI2c; + sint8 s8Ret = M2M_SUCCESS; + + au8Buf[0] = 0x12; + au8Buf[1] = (uint8)(u32Addr >> 24); + au8Buf[2] = (uint8)(u32Addr >> 16); + au8Buf[3] = (uint8)(u32Addr >> 8); + au8Buf[4] = (uint8)(u32Addr); + au8Buf[5] = (uint8)(u16Sz >> 8); + au8Buf[6] = (uint8)(u16Sz); + + strI2c.pu8Buf1 = au8Buf; + strI2c.pu8Buf2 = pu8Buf; + strI2c.u16Sz1 = sizeof(au8Buf); + strI2c.u16Sz2 = u16Sz; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W_SPECIAL, &strI2c)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + + return s8Ret; +} + +#endif +/* EOF */ diff --git a/ext/drivers/atmel/winc1500/driver/source/nmi2c.h b/ext/drivers/atmel/winc1500/driver/source/nmi2c.h new file mode 100755 index 0000000000000..fea85e64c5ec5 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmi2c.h @@ -0,0 +1,104 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 I2C protocol bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NMI2C_H_ +#define _NMI2C_H_ + +#include "common/include/nm_common.h" + +/** +* @fn nm_i2c_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +*/ +uint32 nm_i2c_read_reg(uint32 u32Addr); + +/** +* @fn nm_i2c_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_i2c_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal); + +/** +* @fn nm_i2c_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_i2c_write_reg(uint32 u32Addr, uint32 u32Val); + +/** +* @fn nm_i2c_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u16Sz +* Number of bytes to read. The buffer size must be >= u16Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_i2c_read_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz); + +/** +* @fn nm_i2c_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u16Sz +* Number of bytes to write. The buffer size must be >= u16Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_i2c_write_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz); + +#endif /* _NMI2C_H_ */ diff --git a/ext/drivers/atmel/winc1500/driver/source/nmspi.c b/ext/drivers/atmel/winc1500/driver/source/nmspi.c new file mode 100755 index 0000000000000..996ef92883314 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmspi.c @@ -0,0 +1,876 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 SPI protocol bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +#include "common/include/nm_common.h" + +#ifdef CONF_WINC_USE_SPI + +#define USE_OLD_SPI_SW + +#include "bus_wrapper/include/nm_bus_wrapper.h" +#include "nmspi.h" + +#define NMI_PERIPH_REG_BASE 0x1000 +#define NMI_INTR_REG_BASE (NMI_PERIPH_REG_BASE+0xa00) +#define NMI_CHIPID (NMI_PERIPH_REG_BASE) +#define NMI_PIN_MUX_0 (NMI_PERIPH_REG_BASE + 0x408) +#define NMI_INTR_ENABLE (NMI_INTR_REG_BASE) + +#define NMI_SPI_REG_BASE 0xe800 +#define NMI_SPI_CTL (NMI_SPI_REG_BASE) +#define NMI_SPI_MASTER_DMA_ADDR (NMI_SPI_REG_BASE+0x4) +#define NMI_SPI_MASTER_DMA_COUNT (NMI_SPI_REG_BASE+0x8) +#define NMI_SPI_SLAVE_DMA_ADDR (NMI_SPI_REG_BASE+0xc) +#define NMI_SPI_SLAVE_DMA_COUNT (NMI_SPI_REG_BASE+0x10) +#define NMI_SPI_TX_MODE (NMI_SPI_REG_BASE+0x20) +#define NMI_SPI_PROTOCOL_CONFIG (NMI_SPI_REG_BASE+0x24) +#define NMI_SPI_INTR_CTL (NMI_SPI_REG_BASE+0x2c) + +#define NMI_SPI_PROTOCOL_OFFSET (NMI_SPI_PROTOCOL_CONFIG-NMI_SPI_REG_BASE) + +#define SPI_BASE NMI_SPI_REG_BASE + +#define CMD_DMA_WRITE 0xc1 +#define CMD_DMA_READ 0xc2 +#define CMD_INTERNAL_WRITE 0xc3 +#define CMD_INTERNAL_READ 0xc4 +#define CMD_TERMINATE 0xc5 +#define CMD_REPEAT 0xc6 +#define CMD_DMA_EXT_WRITE 0xc7 +#define CMD_DMA_EXT_READ 0xc8 +#define CMD_SINGLE_WRITE 0xc9 +#define CMD_SINGLE_READ 0xca +#define CMD_RESET 0xcf + +#define N_OK 1 +#define N_FAIL 0 +#define N_RESET -1 +#define N_RETRY -2 + +#define DATA_PKT_SZ_256 256 +#define DATA_PKT_SZ_512 512 +#define DATA_PKT_SZ_1K 1024 +#define DATA_PKT_SZ_4K (4 * 1024) +#define DATA_PKT_SZ_8K (8 * 1024) +#define DATA_PKT_SZ DATA_PKT_SZ_8K + +static uint8 gu8Crc_off = 0; + +static sint8 nmi_spi_read(uint8* b, uint16 sz) +{ + struct nm_spi_rw spi; + spi.in_buffer = NULL; + spi.out_buffer = b; + spi.size = sz; + return nm_bus_ioctl(NM_BUS_IOCTL_RW, &spi); +} + +static sint8 nmi_spi_write(uint8* b, uint16 sz) +{ + struct nm_spi_rw spi; + spi.in_buffer = b; + spi.out_buffer = NULL; + spi.size = sz; + return nm_bus_ioctl(NM_BUS_IOCTL_RW, &spi); +} + +/******************************************** + + Crc7 + +********************************************/ + +static const uint8 crc7_syndrome_table[256] = { + 0x00, 0x09, 0x12, 0x1b, 0x24, 0x2d, 0x36, 0x3f, + 0x48, 0x41, 0x5a, 0x53, 0x6c, 0x65, 0x7e, 0x77, + 0x19, 0x10, 0x0b, 0x02, 0x3d, 0x34, 0x2f, 0x26, + 0x51, 0x58, 0x43, 0x4a, 0x75, 0x7c, 0x67, 0x6e, + 0x32, 0x3b, 0x20, 0x29, 0x16, 0x1f, 0x04, 0x0d, + 0x7a, 0x73, 0x68, 0x61, 0x5e, 0x57, 0x4c, 0x45, + 0x2b, 0x22, 0x39, 0x30, 0x0f, 0x06, 0x1d, 0x14, + 0x63, 0x6a, 0x71, 0x78, 0x47, 0x4e, 0x55, 0x5c, + 0x64, 0x6d, 0x76, 0x7f, 0x40, 0x49, 0x52, 0x5b, + 0x2c, 0x25, 0x3e, 0x37, 0x08, 0x01, 0x1a, 0x13, + 0x7d, 0x74, 0x6f, 0x66, 0x59, 0x50, 0x4b, 0x42, + 0x35, 0x3c, 0x27, 0x2e, 0x11, 0x18, 0x03, 0x0a, + 0x56, 0x5f, 0x44, 0x4d, 0x72, 0x7b, 0x60, 0x69, + 0x1e, 0x17, 0x0c, 0x05, 0x3a, 0x33, 0x28, 0x21, + 0x4f, 0x46, 0x5d, 0x54, 0x6b, 0x62, 0x79, 0x70, + 0x07, 0x0e, 0x15, 0x1c, 0x23, 0x2a, 0x31, 0x38, + 0x41, 0x48, 0x53, 0x5a, 0x65, 0x6c, 0x77, 0x7e, + 0x09, 0x00, 0x1b, 0x12, 0x2d, 0x24, 0x3f, 0x36, + 0x58, 0x51, 0x4a, 0x43, 0x7c, 0x75, 0x6e, 0x67, + 0x10, 0x19, 0x02, 0x0b, 0x34, 0x3d, 0x26, 0x2f, + 0x73, 0x7a, 0x61, 0x68, 0x57, 0x5e, 0x45, 0x4c, + 0x3b, 0x32, 0x29, 0x20, 0x1f, 0x16, 0x0d, 0x04, + 0x6a, 0x63, 0x78, 0x71, 0x4e, 0x47, 0x5c, 0x55, + 0x22, 0x2b, 0x30, 0x39, 0x06, 0x0f, 0x14, 0x1d, + 0x25, 0x2c, 0x37, 0x3e, 0x01, 0x08, 0x13, 0x1a, + 0x6d, 0x64, 0x7f, 0x76, 0x49, 0x40, 0x5b, 0x52, + 0x3c, 0x35, 0x2e, 0x27, 0x18, 0x11, 0x0a, 0x03, + 0x74, 0x7d, 0x66, 0x6f, 0x50, 0x59, 0x42, 0x4b, + 0x17, 0x1e, 0x05, 0x0c, 0x33, 0x3a, 0x21, 0x28, + 0x5f, 0x56, 0x4d, 0x44, 0x7b, 0x72, 0x69, 0x60, + 0x0e, 0x07, 0x1c, 0x15, 0x2a, 0x23, 0x38, 0x31, + 0x46, 0x4f, 0x54, 0x5d, 0x62, 0x6b, 0x70, 0x79 +}; + + +static uint8 crc7_byte(uint8 crc, uint8 data) +{ + return crc7_syndrome_table[(crc << 1) ^ data]; +} + +static uint8 crc7(uint8 crc, const uint8 *buffer, uint32 len) +{ + while (len--) + crc = crc7_byte(crc, *buffer++); + return crc; +} + +/******************************************** + + Spi protocol Function + +********************************************/ + +static sint8 spi_cmd(uint8 cmd, uint32 adr, uint32 u32data, uint32 sz,uint8 clockless) +{ + uint8 bc[9]; + uint8 len = 5; + sint8 result = N_OK; + + bc[0] = cmd; + switch (cmd) { + case CMD_SINGLE_READ: /* single word (4 bytes) read */ + bc[1] = (uint8)(adr >> 16); + bc[2] = (uint8)(adr >> 8); + bc[3] = (uint8)adr; + len = 5; + break; + case CMD_INTERNAL_READ: /* internal register read */ + bc[1] = (uint8)(adr >> 8); + if(clockless) bc[1] |= (1 << 7); + bc[2] = (uint8)adr; + bc[3] = 0x00; + len = 5; + break; + case CMD_TERMINATE: /* termination */ + bc[1] = 0x00; + bc[2] = 0x00; + bc[3] = 0x00; + len = 5; + break; + case CMD_REPEAT: /* repeat */ + bc[1] = 0x00; + bc[2] = 0x00; + bc[3] = 0x00; + len = 5; + break; + case CMD_RESET: /* reset */ + bc[1] = 0xff; + bc[2] = 0xff; + bc[3] = 0xff; + len = 5; + break; + case CMD_DMA_WRITE: /* dma write */ + case CMD_DMA_READ: /* dma read */ + bc[1] = (uint8)(adr >> 16); + bc[2] = (uint8)(adr >> 8); + bc[3] = (uint8)adr; + bc[4] = (uint8)(sz >> 8); + bc[5] = (uint8)(sz); + len = 7; + break; + case CMD_DMA_EXT_WRITE: /* dma extended write */ + case CMD_DMA_EXT_READ: /* dma extended read */ + bc[1] = (uint8)(adr >> 16); + bc[2] = (uint8)(adr >> 8); + bc[3] = (uint8)adr; + bc[4] = (uint8)(sz >> 16); + bc[5] = (uint8)(sz >> 8); + bc[6] = (uint8)(sz); + len = 8; + break; + case CMD_INTERNAL_WRITE: /* internal register write */ + bc[1] = (uint8)(adr >> 8); + if(clockless) bc[1] |= (1 << 7); + bc[2] = (uint8)(adr); + bc[3] = (uint8)(u32data >> 24); + bc[4] = (uint8)(u32data >> 16); + bc[5] = (uint8)(u32data >> 8); + bc[6] = (uint8)(u32data); + len = 8; + break; + case CMD_SINGLE_WRITE: /* single word write */ + bc[1] = (uint8)(adr >> 16); + bc[2] = (uint8)(adr >> 8); + bc[3] = (uint8)(adr); + bc[4] = (uint8)(u32data >> 24); + bc[5] = (uint8)(u32data >> 16); + bc[6] = (uint8)(u32data >> 8); + bc[7] = (uint8)(u32data); + len = 9; + break; + default: + result = N_FAIL; + break; + } + + if (result) { + if (!gu8Crc_off) + bc[len-1] = (crc7(0x7f, (const uint8 *)&bc[0], len-1)) << 1; + else + len-=1; + + if (M2M_SUCCESS != nmi_spi_write(bc, len)) { + M2M_ERR("[nmi spi]: Failed cmd write, bus error...\n"); + result = N_FAIL; + } + } + + return result; +} + +static sint8 spi_cmd_rsp(uint8 cmd) +{ + uint8 rsp; + sint8 result = N_OK; + sint8 s8RetryCnt; + + /** + Command/Control response + **/ + if ((cmd == CMD_RESET) || + (cmd == CMD_TERMINATE) || + (cmd == CMD_REPEAT)) { + if (M2M_SUCCESS != nmi_spi_read(&rsp, 1)) { + result = N_FAIL; + goto _fail_; + } + } + + /* wait for response */ + s8RetryCnt = 10; + do + { + if (M2M_SUCCESS != nmi_spi_read(&rsp, 1)) { + M2M_ERR("[nmi spi]: Failed cmd response read, bus error...\n"); + result = N_FAIL; + goto _fail_; + } + } while((rsp != cmd) && (s8RetryCnt-- >0)); + + /** + State response + **/ + /* wait for response */ + s8RetryCnt = 10; + do + { + if (M2M_SUCCESS != nmi_spi_read(&rsp, 1)) { + M2M_ERR("[nmi spi]: Failed cmd response read, bus error...\n"); + result = N_FAIL; + goto _fail_; + } + } while((rsp != 0x00) && (s8RetryCnt-- >0)); + +_fail_: + + return result; +} + +static sint8 spi_data_read(uint8 *b, uint16 sz,uint8 clockless) +{ + sint16 retry, ix, nbytes; + sint8 result = N_OK; + uint8 crc[2]; + uint8 rsp; + + /** + Data + **/ + ix = 0; + do { + if (sz <= DATA_PKT_SZ) + nbytes = sz; + else + nbytes = DATA_PKT_SZ; + + /** + Data Respnose header + **/ + retry = 10; + do { + if (M2M_SUCCESS != nmi_spi_read(&rsp, 1)) { + M2M_ERR("[nmi spi]: Failed data response read, bus error...\n"); + result = N_FAIL; + break; + } + if (((rsp >> 4) & 0xf) == 0xf) + break; + } while (retry--); + + if (result == N_FAIL) + break; + + if (retry <= 0) { + M2M_ERR("[nmi spi]: Failed data response read...(%02x)\n", rsp); + result = N_FAIL; + break; + } + + /** + Read bytes + **/ + if (M2M_SUCCESS != nmi_spi_read(&b[ix], nbytes)) { + M2M_ERR("[nmi spi]: Failed data block read, bus error...\n"); + result = N_FAIL; + break; + } + if(!clockless) + { + /** + Read Crc + **/ + if (!gu8Crc_off) { + if (M2M_SUCCESS != nmi_spi_read(crc, 2)) { + M2M_ERR("[nmi spi]: Failed data block crc read, bus error...\n"); + result = N_FAIL; + break; + } + } + } + ix += nbytes; + sz -= nbytes; + + } while (sz); + + return result; +} + +static sint8 spi_data_write(uint8 *b, uint16 sz) +{ + sint16 ix; + uint16 nbytes; + sint8 result = 1; + uint8 cmd, order, crc[2] = {0}; + //uint8 rsp; + + /** + Data + **/ + ix = 0; + do { + if (sz <= DATA_PKT_SZ) + nbytes = sz; + else + nbytes = DATA_PKT_SZ; + + /** + Write command + **/ + cmd = 0xf0; + if (ix == 0) { + if (sz <= DATA_PKT_SZ) + order = 0x3; + else + order = 0x1; + } else { + if (sz <= DATA_PKT_SZ) + order = 0x3; + else + order = 0x2; + } + cmd |= order; + if (M2M_SUCCESS != nmi_spi_write(&cmd, 1)) { + M2M_ERR("[nmi spi]: Failed data block cmd write, bus error...\n"); + result = N_FAIL; + break; + } + + /** + Write data + **/ + if (M2M_SUCCESS != nmi_spi_write(&b[ix], nbytes)) { + M2M_ERR("[nmi spi]: Failed data block write, bus error...\n"); + result = N_FAIL; + break; + } + + /** + Write Crc + **/ + if (!gu8Crc_off) { + if (M2M_SUCCESS != nmi_spi_write(crc, 2)) { + M2M_ERR("[nmi spi]: Failed data block crc write, bus error...\n"); + result = N_FAIL; + break; + } + } + + ix += nbytes; + sz -= nbytes; + } while (sz); + + + return result; +} + +/******************************************** + + Spi Internal Read/Write Function + +********************************************/ + +/******************************************** + + Spi interfaces + +********************************************/ + +static sint8 spi_write_reg(uint32 addr, uint32 u32data) +{ + sint8 result = N_OK; + uint8 cmd = CMD_SINGLE_WRITE; + uint8 clockless = 0; + if (addr <= 0x30) + { + /** + NMC1000 clockless registers. + **/ + cmd = CMD_INTERNAL_WRITE; + clockless = 1; + } + else + { + cmd = CMD_SINGLE_WRITE; + clockless = 0; + } + +#if defined USE_OLD_SPI_SW + result = spi_cmd(cmd, addr, u32data, 4, clockless); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd, write reg (%08x)...\n", (unsigned int)addr); + return N_FAIL; + } + + result = spi_cmd_rsp(cmd); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd response, write reg (%08x)...\n", (unsigned int)addr); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + return N_FAIL; + } + + return N_OK; +#else + + result = spi_cmd_complete(cmd, addr, (uint8*)&u32data, 4, clockless); + if (result != N_OK) { + M2M_ERR( "[nmi spi]: Failed cmd, write reg (%08x)...\n", addr); + } + + return result; + +#endif +} + +static sint8 nm_spi_write(uint32 addr, uint8 *buf, uint16 size) +{ + sint8 result; + uint8 cmd = CMD_DMA_EXT_WRITE; + + + /** + Command + **/ +#if defined USE_OLD_SPI_SW + result = spi_cmd(cmd, addr, 0, size,0); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd, write block (%08x)...\n", (unsigned int)addr); + return N_FAIL; + } + + result = spi_cmd_rsp(cmd); + if (result != N_OK) { + M2M_ERR("[nmi spi ]: Failed cmd response, write block (%08x)...\n", (unsigned int)addr); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + return N_FAIL; + } +#else + result = spi_cmd_complete(cmd, addr, NULL, size, 0); + if (result != N_OK) { + M2M_ERR( "[nmi spi]: Failed cmd, write block (%08x)...\n", addr); + return N_FAIL; + } +#endif + + /** + Data + **/ + result = spi_data_write(buf, size); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed block data write...\n"); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + } + + return N_OK; +} + +static sint8 spi_read_reg(uint32 addr, uint32 *u32data) +{ + sint8 result = N_OK; + uint8 cmd = CMD_SINGLE_READ; + uint8 tmp[4]; + uint8 clockless = 0; + + if (addr <= 0xff) + { + /** + NMC1000 clockless registers. + **/ + cmd = CMD_INTERNAL_READ; + clockless = 1; + } + else + { + cmd = CMD_SINGLE_READ; + clockless = 0; + } + +#if defined USE_OLD_SPI_SW + result = spi_cmd(cmd, addr, 0, 4, clockless); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd, read reg (%08x)...\n", (unsigned int)addr); + return N_FAIL; + } + + result = spi_cmd_rsp(cmd); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd response, read reg (%08x)...\n", (unsigned int)addr); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + return N_FAIL; + } + + /* to avoid endianess issues */ + result = spi_data_read(&tmp[0], 4, clockless); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed data read...\n"); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + return N_FAIL; + } +#else + result = spi_cmd_complete(cmd, addr, (uint8*)&tmp[0], 4, clockless); + if (result != N_OK) { + M2M_ERR( "[nmi spi]: Failed cmd, read reg (%08x)...\n", addr); + return N_FAIL; + } + +#endif + + *u32data = tmp[0] | + ((uint32)tmp[1] << 8) | + ((uint32)tmp[2] << 16) | + ((uint32)tmp[3] << 24); + + return N_OK; +} + +static sint8 nm_spi_read(uint32 addr, uint8 *buf, uint16 size) +{ + uint8 cmd = CMD_DMA_EXT_READ; + sint8 result; + + + /** + Command + **/ +#if defined USE_OLD_SPI_SW + result = spi_cmd(cmd, addr, 0, size,0); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd, read block (%08x)...\n", (unsigned int)addr); + return N_FAIL; + } + + result = spi_cmd_rsp(cmd); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd response, read block (%08x)...\n", (unsigned int)addr); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + return N_FAIL; + } + + /** + Data + **/ + result = spi_data_read(buf, size,0); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed block data read...\n"); + spi_cmd(CMD_RESET, 0, 0, 0, 0); + return N_FAIL; + } +#else + result = spi_cmd_complete(cmd, addr, buf, size, 0); + if (result != N_OK) { + M2M_ERR("[nmi spi]: Failed cmd, read block (%08x)...\n", addr); + return N_FAIL; + } +#endif + + return N_OK; +} + +/******************************************** + + Bus interfaces + +********************************************/ + +static void spi_init_pkt_sz(void) +{ + uint32 val32; + + /* Make sure SPI max. packet size fits the defined DATA_PKT_SZ. */ + val32 = nm_spi_read_reg(SPI_BASE+0x24); + val32 &= ~(0x7 << 4); + switch(DATA_PKT_SZ) + { + case 256: val32 |= (0 << 4); break; + case 512: val32 |= (1 << 4); break; + case 1024: val32 |= (2 << 4); break; + case 2048: val32 |= (3 << 4); break; + case 4096: val32 |= (4 << 4); break; + case 8192: val32 |= (5 << 4); break; + + } + nm_spi_write_reg(SPI_BASE+0x24, val32); +} + +/* +* @fn nm_spi_init +* @brief Initialize the SPI +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_spi_init(void) +{ + uint32 chipid; + uint32 reg =0; + + /** + configure protocol + **/ + gu8Crc_off = 0; + + // TODO: We can remove the CRC trials if there is a definite way to reset + // the SPI to it's initial value. + if (!spi_read_reg(NMI_SPI_PROTOCOL_CONFIG, ®)) { + /* Read failed. Try with CRC off. This might happen when module + is removed but chip isn't reset*/ + gu8Crc_off = 1; + M2M_ERR("[nmi spi]: Failed internal read protocol with CRC on, retyring with CRC off...\n"); + if (!spi_read_reg(NMI_SPI_PROTOCOL_CONFIG, ®)){ + // Reaad failed with both CRC on and off, something went bad + M2M_ERR( "[nmi spi]: Failed internal read protocol...\n"); + return 0; + } + } + if(gu8Crc_off == 0) + { + reg &= ~0xc; /* disable crc checking */ + reg &= ~0x70; + reg |= (0x5 << 4); + if (!spi_write_reg(NMI_SPI_PROTOCOL_CONFIG, reg)) { + M2M_ERR( "[nmi spi]: Failed internal write protocol reg...\n"); + return 0; + } + gu8Crc_off = 1; + } + + /** + make sure can read back chip id correctly + **/ + if (!spi_read_reg(0x1000, &chipid)) { + M2M_ERR("[nmi spi]: Fail cmd read chip id...\n"); + return M2M_ERR_BUS_FAIL; + } + + M2M_DBG("[nmi spi]: chipid (%08x)\n", (unsigned int)chipid); + spi_init_pkt_sz(); + + + return M2M_SUCCESS; +} + +/* +* @fn nm_spi_init +* @brief DeInitialize the SPI +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Samer Sarhan +* @date 27 Feb 2015 +* @version 1.0 +*/ +sint8 nm_spi_deinit(void) +{ + gu8Crc_off = 0; + return M2M_SUCCESS; +} + +/* +* @fn nm_spi_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +uint32 nm_spi_read_reg(uint32 u32Addr) +{ + uint32 u32Val; + + spi_read_reg(u32Addr, &u32Val); + + return u32Val; +} + +/* +* @fn nm_spi_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_spi_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal) +{ + sint8 s8Ret; + + s8Ret = spi_read_reg(u32Addr,pu32RetVal); + + if(N_OK == s8Ret) s8Ret = M2M_SUCCESS; + else s8Ret = M2M_ERR_BUS_FAIL; + + return s8Ret; +} + +/* +* @fn nm_spi_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_spi_write_reg(uint32 u32Addr, uint32 u32Val) +{ + sint8 s8Ret; + + s8Ret = spi_write_reg(u32Addr, u32Val); + + if(N_OK == s8Ret) s8Ret = M2M_SUCCESS; + else s8Ret = M2M_ERR_BUS_FAIL; + + return s8Ret; +} + +/* +* @fn nm_spi_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u16Sz +* Number of bytes to read. The buffer size must be >= u16Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_spi_read_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz) +{ + sint8 s8Ret; + + s8Ret = nm_spi_read(u32Addr, puBuf, u16Sz); + + if(N_OK == s8Ret) s8Ret = M2M_SUCCESS; + else s8Ret = M2M_ERR_BUS_FAIL; + + return s8Ret; +} + +/* +* @fn nm_spi_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u16Sz +* Number of bytes to write. The buffer size must be >= u16Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author M. Abdelmawla +* @date 11 July 2012 +* @version 1.0 +*/ +sint8 nm_spi_write_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz) +{ + sint8 s8Ret; + + s8Ret = nm_spi_write(u32Addr, puBuf, u16Sz); + + if(N_OK == s8Ret) s8Ret = M2M_SUCCESS; + else s8Ret = M2M_ERR_BUS_FAIL; + + return s8Ret; +} + +#endif diff --git a/ext/drivers/atmel/winc1500/driver/source/nmspi.h b/ext/drivers/atmel/winc1500/driver/source/nmspi.h new file mode 100755 index 0000000000000..521de91d7b60c --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmspi.h @@ -0,0 +1,126 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 SPI protocol bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NMSPI_H_ +#define _NMSPI_H_ + +#include "common/include/nm_common.h" + +#ifdef __cplusplus + extern "C" { +#endif + +/** +* @fn nm_spi_init +* @brief Initialize the SPI +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_spi_init(void); + +/** +* @fn nm_spi_deinit +* @brief DeInitialize the SPI +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_spi_deinit(void); + +/** +* @fn nm_spi_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +*/ +uint32 nm_spi_read_reg(uint32 u32Addr); + +/** +* @fn nm_spi_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_spi_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal); + +/** +* @fn nm_spi_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_spi_write_reg(uint32 u32Addr, uint32 u32Val); + +/** +* @fn nm_spi_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u16Sz +* Number of bytes to read. The buffer size must be >= u16Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_spi_read_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz); + +/** +* @fn nm_spi_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u16Sz +* Number of bytes to write. The buffer size must be >= u16Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_spi_write_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz); + +#ifdef __cplusplus + } +#endif + +#endif /* _NMSPI_H_ */ diff --git a/ext/drivers/atmel/winc1500/driver/source/nmuart.c b/ext/drivers/atmel/winc1500/driver/source/nmuart.c new file mode 100755 index 0000000000000..3062391266169 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmuart.c @@ -0,0 +1,547 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 UART protocol bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "common/include/nm_common.h" + +#ifdef CONF_WINC_USE_UART + +#include "driver/source/nmuart.h" +#include "bus_wrapper/include/nm_bus_wrapper.h" + +#define HDR_SZ 12 + +/** +* @struct tstrNmUartDefault +* @brief Structure holding UART default operation parameters +* @sa NM_BUS_IOCTL_R, NM_BUS_IOCTL_W +*/ +typedef struct +{ + u8_t *pu8Buf; /*!< Operation buffer */ + u16_t u16Sz; /*!< Operation size */ +} tstrNmUartDefault; + +static uint8 get_cs(uint8* b, uint8 sz){ + int i; + uint8 cs = 0; + for(i = 0; i < sz; i++) + cs ^= b[i]; + return cs; +} + +/* +* @fn nm_uart_sync_cmd +* @brief Check COM Port +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Dina El Sissy +* @date 13 AUG 2012 +* @version 1.0 +*/ +sint8 nm_uart_sync_cmd(void) +{ + tstrNmUartDefault strUart; + sint8 s8Ret = -1; + uint8 b [HDR_SZ+1]; + uint8 rsz; + uint8 onchip = 0; + + /*read reg*/ + b[0] = 0x12; + + rsz = 1; + strUart.pu8Buf = b; + strUart.u16Sz = 1; + + if(M2M_SUCCESS == nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + strUart.u16Sz = rsz; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + M2M_ERR("failed to send cfg bytes\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + if (b[0] == 0x5a) + { + s8Ret = 0; + onchip = 1; + M2M_INFO("Built-in WINC1500 UART Found\n"); + } + else if(b[0] == 0x5b) + { + s8Ret = 0; + onchip = 0; + M2M_INFO("WINC1500 Serial Bridge Found\n"); + } + /*TODO: this should be the way we read the register since the cortus is little endian*/ + /**pu32RetVal = b[0] | ((uint32)b[1] << 8) | ((uint32)b[2] << 16) | ((uint32)b[3] << 24);*/ + if(s8Ret == M2M_SUCCESS) + s8Ret = (sint8)onchip; + return s8Ret; +} + sint8 nm_uart_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal) +{ + tstrNmUartDefault strUart; + sint8 s8Ret = M2M_SUCCESS; + uint8 b [HDR_SZ+1]; + uint8 rsz; + + /*read reg*/ + b[0] = 0xa5; + b[1] = 0; + b[2] = 0; + b[3] = 0; + b[4] = 0; + b[5] = (uint8)(u32Addr & 0x000000ff); + b[6] = (uint8)((u32Addr & 0x0000ff00)>>8); + b[7] = (uint8)((u32Addr & 0x00ff0000)>>16); + b[8] = (uint8)((u32Addr & 0xff000000)>>24); + b[9] = 0; + b[10] = 0; + b[11] = 0; + b[12] = 0; + + b[2] = get_cs(&b[1],HDR_SZ); + + rsz = 4; + strUart.pu8Buf = b; + strUart.u16Sz = sizeof(b); + + if(M2M_SUCCESS == nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + if(!nm_bus_get_chip_type()) + { + strUart.u16Sz = 1; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + if(b[0] == 0xAC) + { + M2M_DBG("Successfully sent the command\n"); + strUart.u16Sz = rsz; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + strUart.u16Sz = rsz; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + } + } + else + { + M2M_ERR("failed to send cfg bytes\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + /*TODO: this should be the way we read the register since the cortus is little endian*/ + /**pu32RetVal = b[0] | ((uint32)b[1] << 8) | ((uint32)b[2] << 16) | ((uint32)b[3] << 24);*/ + + *pu32RetVal = ((uint32)b[0] << 24) | ((uint32)b[1] << 16) | ((uint32)b[2] << 8) | b[3]; + + return s8Ret; +} + +/* +* @fn nm_uart_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +* @author Dina El Sissy +* @date 13 AUG 2012 +* @version 1.0 +*/ +uint32 nm_uart_read_reg(uint32 u32Addr) +{ + uint32 val; + nm_uart_read_reg_with_ret(u32Addr , &val); + return val; +} + +/* +* @fn nm_uart_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Dina El Sissy +* @date 13 AUG 2012 +* @version 1.0 +*/ +sint8 nm_uart_write_reg(uint32 u32Addr, uint32 u32Val) +{ + tstrNmUartDefault strUart; + sint8 s8Ret = M2M_SUCCESS; + uint8 b[HDR_SZ+1]; + + /*write reg*/ + b[0] = 0xa5; + b[1] = 1; + b[2] = 0; + b[3] = 0; + b[4] = 0; + b[5] = (uint8)(u32Addr & 0x000000ff); + b[6] = (uint8)((u32Addr & 0x0000ff00)>>8); + b[7] = (uint8)((u32Addr & 0x00ff0000)>>16); + b[8] = (uint8)((u32Addr & 0xff000000)>>24); + b[9] = (uint8)(u32Val & 0x000000ff); + b[10] = (uint8)((u32Val & 0x0000ff00)>>8); + b[11] = (uint8)((u32Val & 0x00ff0000)>>16); + b[12] = (uint8)((u32Val & 0xff000000)>>24); + + b[2] = get_cs(&b[1],HDR_SZ); + + get_cs(&b[1],HDR_SZ); + + strUart.pu8Buf = b; + strUart.u16Sz = sizeof(b); + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + else + { + if(!nm_bus_get_chip_type()) + { + //check for the ack from the SAMD21 for the packet reception. + strUart.u16Sz = 1; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + if(b[0] == 0xAC) + { + M2M_DBG("Successfully sent the reg write command\n"); + } + else + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + } + + return s8Ret; +} + + +/** +* @fn nm_uart_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u16Sz +* Number of bytes to read. The buffer size must be >= u16Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Dina El Sissy +* @date 13 AUG 2012 +* @version 1.0 +*/ +sint8 nm_uart_read_block(uint32 u32Addr, uint8 *pu8Buf, uint16 u16Sz) +{ + tstrNmUartDefault strUart; + sint8 s8Ret = M2M_SUCCESS; + uint8 au8Buf[HDR_SZ+1]; + + au8Buf[0] = 0xa5; + au8Buf[1] = 2; + au8Buf[2] = 0; + au8Buf[3] = (uint8)(u16Sz & 0x00ff); + au8Buf[4] = (uint8)((u16Sz & 0xff00)>>8); + au8Buf[5] = (uint8)(u32Addr & 0x000000ff); + au8Buf[6] = (uint8)((u32Addr & 0x0000ff00)>>8); + au8Buf[7] = (uint8)((u32Addr & 0x00ff0000)>>16); + au8Buf[8] = (uint8)((u32Addr & 0xff000000)>>24); + au8Buf[9] = 0; + au8Buf[10] = 0; + au8Buf[11] = 0; + au8Buf[12] = 0; + + au8Buf[2] = get_cs(&au8Buf[1],HDR_SZ); + + strUart.pu8Buf = au8Buf; + strUart.u16Sz = sizeof(au8Buf); + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + else + { + if(!nm_bus_get_chip_type()) + { + //check for the ack from the SAMD21 for the packet reception. + strUart.u16Sz = 1; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + if(au8Buf[0] == 0xAC) + { + M2M_DBG("Successfully sent the block read command\n"); + strUart.pu8Buf = pu8Buf; + strUart.u16Sz = u16Sz; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + M2M_ERR("read error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + M2M_ERR("write error (Error sending the block read command)\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + strUart.pu8Buf = pu8Buf; + strUart.u16Sz = u16Sz; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + M2M_ERR("read error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + } + + return s8Ret; +} + +/** +* @fn nm_uart_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u16Sz +* Number of bytes to write. The buffer size must be >= u16Sz +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Dina El Sissy +* @date 13 AUG 2012 +* @version 1.0 +*/ +sint8 nm_uart_write_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz) +{ + tstrNmUartDefault strUart; + sint8 s8Ret = M2M_SUCCESS; + static uint8 au8Buf[HDR_SZ+1]; + + au8Buf[0] = 0xa5; + au8Buf[1] = 3; + au8Buf[2] = 0; + au8Buf[3] = (uint8)(u16Sz & 0x00ff); + au8Buf[4] = (uint8)((u16Sz & 0xff00)>>8); + au8Buf[5] = (uint8)(u32Addr & 0x000000ff); + au8Buf[6] = (uint8)((u32Addr & 0x0000ff00)>>8); + au8Buf[7] = (uint8)((u32Addr & 0x00ff0000)>>16); + au8Buf[8] = (uint8)((u32Addr & 0xff000000)>>24); + au8Buf[9] = 0; + au8Buf[10] = 0; + au8Buf[11] = 0; + au8Buf[12] = 0; + + au8Buf[2] = get_cs(&au8Buf[1],HDR_SZ); + + strUart.pu8Buf = au8Buf; + strUart.u16Sz = sizeof(au8Buf); + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + else + { + if(!nm_bus_get_chip_type()) + { + //check for the ack from the SAMD21 for the packet reception. + strUart.u16Sz = 1; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + if(au8Buf[0] == 0xAC) + { + M2M_DBG("Successfully sent the block Write command\n"); + strUart.pu8Buf = puBuf; + strUart.u16Sz = u16Sz; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + else + { + //check for the ack from the SAMD21 for the payload reception. + strUart.pu8Buf = au8Buf; + strUart.u16Sz = 1; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + if(au8Buf[0] == 0xAC) + { + M2M_DBG("Successfully sent the data payload\n"); + } + else + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + } + else + { + M2M_ERR("write error (Error sending the block write command)\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + else + { + strUart.pu8Buf = puBuf; + strUart.u16Sz = u16Sz; + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + } + return s8Ret; +} + +/** +* @fn nm_uart_reconfigure +* @brief Reconfigures the UART interface +* @param [in] ptr +* Pointer to a DWORD containing baudrate at this moment. +* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure +* @author Viswanathan Murugesan +* @date 22 OCT 2014 +* @version 1.0 +*/ +sint8 nm_uart_reconfigure(void *ptr) +{ + tstrNmUartDefault strUart; + sint8 s8Ret = M2M_SUCCESS; + uint8 b[HDR_SZ+1]; + + /*write reg*/ + b[0] = 0xa5; + b[1] = 5; + b[2] = 0; + b[3] = 0; + b[4] = 0; + b[5] = 0; + b[6] = 0; + b[7] = 0; + b[8] = 0; + b[9] = (uint8)((*(unsigned long *)ptr) & 0x000000ff); + b[10] = (uint8)(((*(unsigned long *)ptr) & 0x0000ff00)>>8); + b[11] = (uint8)(((*(unsigned long *)ptr) & 0x00ff0000)>>16); + b[12] = (uint8)(((*(unsigned long *)ptr) & 0xff000000)>>24); + + b[2] = get_cs(&b[1],HDR_SZ); + + get_cs(&b[1],HDR_SZ); + + strUart.pu8Buf = b; + strUart.u16Sz = sizeof(b); + + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_W, &strUart)) + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + else + { + if(!nm_bus_get_chip_type()) + { + //check for the ack from the SAMD21 for the packet reception. + strUart.u16Sz = 1; + if(M2M_SUCCESS != nm_bus_ioctl(NM_BUS_IOCTL_R, &strUart)) + { + s8Ret = M2M_ERR_BUS_FAIL; + } + if(b[0] == 0xAC) + { + M2M_DBG("Successfully sent the UART reconfigure command\n"); + } + else + { + M2M_ERR("write error\n"); + s8Ret = M2M_ERR_BUS_FAIL; + } + } + } + + return s8Ret; +} +#endif +/* EOF */ diff --git a/ext/drivers/atmel/winc1500/driver/source/nmuart.h b/ext/drivers/atmel/winc1500/driver/source/nmuart.h new file mode 100755 index 0000000000000..8f07d39e1b606 --- /dev/null +++ b/ext/drivers/atmel/winc1500/driver/source/nmuart.h @@ -0,0 +1,118 @@ +/** + * + * \file + * + * \brief This module contains NMC1000 UART protocol bus APIs implementation. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef _NMUART_H_ +#define _NMUART_H_ + +#include "common/include/nm_common.h" + +/* +* @fn nm_uart_sync_cmd +* @brief Check COM Port +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_uart_sync_cmd(void); +/** +* @fn nm_uart_read_reg +* @brief Read register +* @param [in] u32Addr +* Register address +* @return Register value +*/ +uint32 nm_uart_read_reg(uint32 u32Addr); + +/** +* @fn nm_uart_read_reg_with_ret +* @brief Read register with error code return +* @param [in] u32Addr +* Register address +* @param [out] pu32RetVal +* Pointer to u32 variable used to return the read value +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_uart_read_reg_with_ret(uint32 u32Addr, uint32* pu32RetVal); + +/** +* @fn nm_uart_write_reg +* @brief write register +* @param [in] u32Addr +* Register address +* @param [in] u32Val +* Value to be written to the register +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_uart_write_reg(uint32 u32Addr, uint32 u32Val); + +/** +* @fn nm_uart_read_block +* @brief Read block of data +* @param [in] u32Addr +* Start address +* @param [out] puBuf +* Pointer to a buffer used to return the read data +* @param [in] u16Sz +* Number of bytes to read. The buffer size must be >= u16Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_uart_read_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz); + +/** +* @fn nm_uart_write_block +* @brief Write block of data +* @param [in] u32Addr +* Start address +* @param [in] puBuf +* Pointer to the buffer holding the data to be written +* @param [in] u16Sz +* Number of bytes to write. The buffer size must be >= u16Sz +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_uart_write_block(uint32 u32Addr, uint8 *puBuf, uint16 u16Sz); + +/** +* @fn nm_uart_reconfigure +* @brief Reconfigures the UART interface +* @param [in] ptr +* Pointer to a DWORD containing baudrate at this moment. +* @return ZERO in case of success and M2M_ERR_BUS_FAIL in case of failure +*/ +sint8 nm_uart_reconfigure(void *ptr); +#endif /* _NMI2C_H_ */ diff --git a/ext/drivers/atmel/winc1500/socket/include/m2m_socket_host_if.h b/ext/drivers/atmel/winc1500/socket/include/m2m_socket_host_if.h new file mode 100644 index 0000000000000..88e236582fd3e --- /dev/null +++ b/ext/drivers/atmel/winc1500/socket/include/m2m_socket_host_if.h @@ -0,0 +1,421 @@ +/** + * + * \file + * + * \brief BSD alike socket interface internal types. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +#ifndef __M2M_SOCKET_HOST_IF_H__ +#define __M2M_SOCKET_HOST_IF_H__ + + +#ifdef __cplusplus +extern "C" { +#endif + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#ifndef _BOOT_ +#ifndef _FIRMWARE_ +#include "socket/include/socket.h" +#else +#include "m2m_types.h" +#endif +#endif + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#ifdef _FIRMWARE_ +#define HOSTNAME_MAX_SIZE (64) +#endif + +#define SSL_MAX_OPT_LEN HOSTNAME_MAX_SIZE + + + +#define SOCKET_CMD_INVALID 0x00 +/*!< + Invlaid Socket command value. +*/ + + +#define SOCKET_CMD_BIND 0x41 +/*!< + Socket Binding command value. +*/ + + +#define SOCKET_CMD_LISTEN 0x42 +/*!< + Socket Listening command value. +*/ + + +#define SOCKET_CMD_ACCEPT 0x43 +/*!< + Socket Accepting command value. +*/ + + +#define SOCKET_CMD_CONNECT 0x44 +/*!< + Socket Connecting command value. +*/ + + +#define SOCKET_CMD_SEND 0x45 +/*!< + Socket send command value. +*/ + + +#define SOCKET_CMD_RECV 0x46 +/*!< + Socket Recieve command value. +*/ + + +#define SOCKET_CMD_SENDTO 0x47 +/*!< + Socket sendTo command value. +*/ + + +#define SOCKET_CMD_RECVFROM 0x48 +/*!< + Socket RecieveFrom command value. +*/ + + +#define SOCKET_CMD_CLOSE 0x49 +/*!< + Socket Close command value. +*/ + + +#define SOCKET_CMD_DNS_RESOLVE 0x4A +/*!< + Socket DNS Resolve command value. +*/ + + +#define SOCKET_CMD_SSL_CONNECT 0x4B +/*!< + SSL-Socket Connect command value. +*/ + + +#define SOCKET_CMD_SSL_SEND 0x4C +/*!< + SSL-Socket Send command value. +*/ + + +#define SOCKET_CMD_SSL_RECV 0x4D +/*!< + SSL-Socket Recieve command value. +*/ + + +#define SOCKET_CMD_SSL_CLOSE 0x4E +/*!< + SSL-Socket Close command value. +*/ + + +#define SOCKET_CMD_SET_SOCKET_OPTION 0x4F +/*!< + Set Socket Option command value. +*/ + + +#define SOCKET_CMD_SSL_CREATE 0x50 +/*!< +*/ + + +#define SOCKET_CMD_SSL_SET_SOCK_OPT 0x51 + + +#define SOCKET_CMD_PING 0x52 + +#define SOCKET_CMD_SSL_SET_CS_LIST 0x53 + + +#define PING_ERR_SUCCESS 0 +#define PING_ERR_DEST_UNREACH 1 +#define PING_ERR_TIMEOUT 2 + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +/*! +* @brief +*/ +typedef struct{ + uint16 u16Family; + uint16 u16Port; + uint32 u32IPAddr; +}tstrSockAddr; + + +typedef sint8 SOCKET; +typedef tstrSockAddr tstrUIPSockAddr; + + + +/*! +@struct \ + tstrDnsReply + +@brief + DNS Reply, contains hostName and HostIP. +*/ +typedef struct{ + char acHostName[HOSTNAME_MAX_SIZE]; + uint32 u32HostIP; +}tstrDnsReply; + + +/*! +@brief +*/ +typedef struct{ + tstrSockAddr strAddr; + SOCKET sock; + uint8 u8Void; + uint16 u16SessionID; +}tstrBindCmd; + + +/*! +@brief +*/ +typedef struct{ + SOCKET sock; + sint8 s8Status; + uint16 u16SessionID; +}tstrBindReply; + + +/*! +* @brief +*/ +typedef struct{ + SOCKET sock; + uint8 u8BackLog; + uint16 u16SessionID; +}tstrListenCmd; + + +/*! +@struct \ + tstrSocketRecvMsg + +@brief Socket recv status. + + It is passed to the APPSocketEventHandler with SOCKET_MSG_RECV or SOCKET_MSG_RECVFROM message type + in a response to a user call to the recv or recvfrom. + If the received data from the remote peer is larger than the USER Buffer size (given at recv call), the data is + delivered to the user in a number of consecutive chunks according to the USER Buffer size. +*/ +typedef struct{ + SOCKET sock; + sint8 s8Status; + uint16 u16SessionID; +}tstrListenReply; + + +/*! +* @brief +*/ +typedef struct{ + tstrSockAddr strAddr; + SOCKET sListenSock; + SOCKET sConnectedSock; + uint16 u16Void; +}tstrAcceptReply; + + +/*! +* @brief +*/ +typedef struct{ + tstrSockAddr strAddr; + SOCKET sock; + uint8 u8SslFlags; + uint16 u16SessionID; +}tstrConnectCmd; + + +/*! +@struct \ + tstrConnectReply + +@brief + Connect Reply, contains sock number and error value +*/ +typedef struct{ + SOCKET sock; + sint8 s8Error; + uint16 u16AppDataOffset; + /*!< + In further packet send requests the host interface should put the user application + data at this offset in the allocated shared data packet. + */ +}tstrConnectReply; + + +/*! +@brief +*/ +typedef struct{ + SOCKET sock; + uint8 u8Void; + uint16 u16DataSize; + tstrSockAddr strAddr; + uint16 u16SessionID; + uint16 u16Void; +}tstrSendCmd; + + +/*! +@struct \ + tstrSendReply + +@brief + Send Reply, contains socket number and number of sent bytes. +*/ +typedef struct{ + SOCKET sock; + uint8 u8Void; + sint16 s16SentBytes; + uint16 u16SessionID; + uint16 u16Void; +}tstrSendReply; + + +/*! +* @brief +*/ +typedef struct{ + uint32 u32Timeoutmsec; + SOCKET sock; + uint8 u8Void; + uint16 u16SessionID; +}tstrRecvCmd; + + +/*! +@struct +@brief +*/ +typedef struct{ + tstrSockAddr strRemoteAddr; + sint16 s16RecvStatus; + uint16 u16DataOffset; + SOCKET sock; + uint8 u8Void; + uint16 u16SessionID; +}tstrRecvReply; + + +/*! +* @brief +*/ +typedef struct{ + uint32 u32OptionValue; + SOCKET sock; + uint8 u8Option; + uint16 u16SessionID; +}tstrSetSocketOptCmd; + + +typedef struct{ + SOCKET sslSock; + uint8 __PAD24__[3]; +}tstrSSLSocketCreateCmd; + + +/*! +* @brief +*/ +typedef struct{ + SOCKET sock; + uint8 u8Option; + uint16 u16SessionID; + uint32 u32OptLen; + uint8 au8OptVal[SSL_MAX_OPT_LEN]; +}tstrSSLSetSockOptCmd; + + +/*! +*/ +typedef struct{ + uint32 u32DestIPAddr; + uint32 u32CmdPrivate; + uint16 u16PingCount; + uint8 u8TTL; + uint8 __PAD8__; +}tstrPingCmd; + + +typedef struct{ + uint32 u32IPAddr; + uint32 u32CmdPrivate; + uint32 u32RTT; + uint16 u16Success; + uint16 u16Fail; + uint8 u8ErrorCode; + uint8 __PAD24__[3]; +}tstrPingReply; + + +typedef struct{ + uint32 u32CsBMP; +}tstrSslSetActiveCsList; + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* __M2M_SOCKET_HOST_IF_H__ */ diff --git a/ext/drivers/atmel/winc1500/socket/include/socket.h b/ext/drivers/atmel/winc1500/socket/include/socket.h new file mode 100644 index 0000000000000..6f24205ad2e93 --- /dev/null +++ b/ext/drivers/atmel/winc1500/socket/include/socket.h @@ -0,0 +1,1940 @@ +/** + * + * \file + * + * \brief BSD alike socket interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef __SOCKET_H__ +#define __SOCKET_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/** \defgroup SocketHeader Socket + * BSD alike socket interface beftween the host layer and the network + * protocol stacks in the firmware. + * These functions are used by the host application to send or receive + * packets and to do other socket operations. + */ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "common/include/nm_common.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/** + * @defgroup SocketDefines Defines + * @ingroup SocketHeader + */ + +/** @defgroup IPDefines TCP/IP Defines + * @ingroup SocketDefines + * The following list of macros are used to define constants used throughout the socket layer. + * @{ + */ +#define HOSTNAME_MAX_SIZE 64 +/*!< + Maximum allowed size for a host domain name passed to the function gethostbyname @ref gethostbyname. + command value. Used with the setsockopt function. + +*/ + +#define SOCKET_BUFFER_MAX_LENGTH 1400 +/*!< + Maximum allowed size for a socket data buffer. Used with @ref send socket + function to ensure that the buffer sent is within the allowed range. +*/ +/* FIXME + * this conflicts with zephyr's symbols + */ +#ifndef __ZEPHYR__ +#define AF_INET 2 +#else +#include +#endif +/*!< + The AF_INET is the address family used for IPv4. An IPv4 transport address is specified with the @ref sockaddr_in structure. + (It is the only supported type for the current implementation.) +*/ + + +#define SOCK_STREAM 1 +/*!< + One of the IPv4 supported socket types for reliable connection-oriented stream connection. + Passed to the @ref socket function for the socket creation operation. +*/ + +#define SOCK_DGRAM 2 +/*!< + One of the IPv4 supported socket types for unreliable connectionless datagram connection. + Passed to the @ref socket function for the socket creation operation. +*/ + + +#define SOCKET_FLAGS_SSL 0x01 +/*!< + This flag shall be passed to the socket API for SSL session. +*/ + +#define TCP_SOCK_MAX (7) +/*!< + Maximum number of simultaneous TCP sockets. +*/ + +#define UDP_SOCK_MAX 4 +/*!< + Maximum number of simultaneous UDP sockets. +*/ + +#define MAX_SOCKET (TCP_SOCK_MAX + UDP_SOCK_MAX) +/*!< + Maximum number of Sockets. +*/ + +#define SOL_SOCKET 1 +/*!< + Socket option. + Used with the @ref setsockopt function +*/ + +#define SOL_SSL_SOCKET 2 +/*!< + SSL Socket option level. + Used with the @ref setsockopt function +*/ + +#define SO_SET_UDP_SEND_CALLBACK 0x00 +/*!< + Socket option used by the application to enable/disable + the use of UDP send callbacks. + Used with the @ref setsockopt function. +*/ + +#define IP_ADD_MEMBERSHIP 0x01 +/*!< + Set Socket Option Add Membership command value. + Used with the @ref setsockopt function. +*/ + + +#define IP_DROP_MEMBERSHIP 0x02 +/*!< + Set Socket Option Drop Membership command value. + Used with the @ref setsockopt function. +*/ + //@} + + + +/** + * @defgroup TLSDefines TLS Defines + * @ingroup SocketDefines + */ + + + +/** @defgroup SSLSocketOptions TLS Socket Options + * @ingroup TLSDefines + * The following list of macros are used to define SSL Socket options. + * @{ + * @sa setsockopt + */ + +#define SO_SSL_BYPASS_X509_VERIF 0x01 +/*!< + Allow an opened SSL socket to bypass the X509 certificate + verification process. + It is highly required NOT to use this socket option in production + software applications. It is supported for debugging and testing + purposes. + The option value should be casted to int type and it is handled + as a boolean flag. +*/ + + +#define SO_SSL_SNI 0x02 +/*!< + Set the Server Name Indicator (SNI) for an SSL socket. The + SNI is a NULL terminated string containing the server name + assocated with the connection. It must not exceed the size + of HOSTNAME_MAX_SIZE. +*/ + + +#define SO_SSL_ENABLE_SESSION_CACHING 0x03 +/*!< + This option allow the TLS to cache the session information for fast + TLS session establishment in future connections using the + TLS Protocol session resume features. +*/ + +//@} + + + +/** @defgroup SSLCipherSuiteConfiguration TLS Cipher Suite Configurations + * @ingroup TLSDefines + * The following list of macros are used to define SSL Ciphersuite Configuration. + * @sa sslSetActiveCipherSuites + * @{ + */ + +#define SSL_ENABLE_ALL_SUITES 0xfffffffful +/*!< + Enable all possible supported cipher suites. +*/ + +#define SSL_ENABLE_RSA_SHA_SUITES 0x01 +/*!< + Enable RSA Hmac_SHA based Ciphersuites. For example, + TLS_RSA_WITH_AES_128_CBC_SHA +*/ + + +#define SSL_ENABLE_RSA_SHA256_SUITES 0x02 +/*!< + Enable RSA Hmac_SHA256 based Ciphersuites. For example, + TLS_RSA_WITH_AES_128_CBC_SHA256 +*/ + + +#define SSL_ENABLE_DHE_SHA_SUITES 0x04 +/*!< + Enable DHE Hmac_SHA based Ciphersuites. For example, + TLS_DHE_RSA_WITH_AES_128_CBC_SHA +*/ + + +#define SSL_ENABLE_DHE_SHA256_SUITES 0x08 +/*!< + Enable DHE Hmac_SHA256 based Ciphersuites. For example, + TLS_DHE_RSA_WITH_AES_128_CBC_SHA256 +*/ + + +#define SSL_ENABLE_RSA_GCM_SUITES 0x10 +/*!< + Enable RSA AEAD based Ciphersuites. For example, + TLS_RSA_WITH_AES_128_GCM_SHA256 +*/ + + +#define SSL_ENABLE_DHE_GCM_SUITES 0x20 +/*!< + Enable DHE AEAD based Ciphersuites. For example, + TLS_DHE_RSA_WITH_AES_128_GCM_SHA256 +*/ + + //@} + + + + + +/************** +Socket Errors +**************/ +/**@defgroup SocketErrorCode Error Codes + * @ingroup SocketHeader + * The following list of macros are used to define the possible error codes returned as a result of a call to a socket function. + * Errors are listed in numerical order with the error macro name. + * @{ + */ +#define SOCK_ERR_NO_ERROR 0 +/*!< + Successfull socket operation +*/ + + +#define SOCK_ERR_INVALID_ADDRESS -1 +/*!< + Socket address is invalid. The socket operation cannot be completed successfully without specifying a specific address + For example: bind is called without specifying a port number +*/ + + +#define SOCK_ERR_ADDR_ALREADY_IN_USE -2 +/*!< + Socket operation cannot bind on the given address. With socket operations, only one IP address per socket is permitted. + Any attempt for a new socket to bind with an IP address already bound to another open socket, + will return the following error code. States that bind operation failed. +*/ + + +#define SOCK_ERR_MAX_TCP_SOCK -3 +/*!< + Exceeded the maximum number of TCP sockets. A maximum number of TCP sockets opened simultaneously is defined through TCP_SOCK_MAX. + It is not permitted to exceed that number at socket creation. Identifies that @ref socket operation failed. +*/ + + +#define SOCK_ERR_MAX_UDP_SOCK -4 +/*!< + Exceeded the maximum number of UDP sockets. A maximum number of UDP sockets opened simultaneously is defined through UDP_SOCK_MAX. + It is not permitted to exceed that number at socket creation. Identifies that @ref socket operation failed +*/ + + +#define SOCK_ERR_INVALID_ARG -6 +/*!< + An invalid arguement is passed to a function. +*/ + + +#define SOCK_ERR_MAX_LISTEN_SOCK -7 +/*!< + Exceeded the maximum number of TCP passive listening sockets. + Identifies Identifies that @ref listen operation failed. +*/ + + +#define SOCK_ERR_INVALID -9 +/*!< + The requested socket operation is not valid in the + current socket state. + For example: @ref accept is called on a TCP socket before @ref bind or @ref listen. +*/ + + +#define SOCK_ERR_ADDR_IS_REQUIRED -11 +/*!< + Destination address is required. Failure to provide the socket address required for the socket operation to be completed. + It is generated as an error to the @ref sendto function when the address required to send the data to is not known. +*/ + + +#define SOCK_ERR_CONN_ABORTED -12 +/*!< + The socket is closed by the peer. The local socket is + closed also. +*/ + + +#define SOCK_ERR_TIMEOUT -13 +/*!< + The socket pending operation has timedout. +*/ + + +#define SOCK_ERR_BUFFER_FULL -14 +/*!< + No buffer space available to be used for the requested socket operation. +*/ + +#ifdef _NM_BSP_BIG_END + +#define _htonl(m) (m) +#define _htons(A) (A) + +#else + +#define _htonl(m) \ + (uint32)(((uint32)(m << 24)) | ((uint32)((m & 0x0000FF00) << 8)) | ((uint32)((m & 0x00FF0000) >> 8)) | ((uint32)(m >> 24))) +/*!< + Convert a 4-byte integer from the host representation to the Network byte order representation. +*/ + + +#define _htons(A) (uint16)((((uint16) (A)) << 8) | (((uint16) (A)) >> 8)) +/*!< + Convert a 2-byte integer (short) from the host representation to the Network byte order representation. +*/ + + +#endif + + +#define _ntohl _htonl +/*!< + Convert a 4-byte integer from the Network byte order representation to the host representation . +*/ + + +#define _ntohs _htons +/*!< + Convert a 2-byte integer from the Network byte order representation to the host representation . +*/ + //@} + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/** @defgroup SocketEnums Enumeration-Typedef + * @ingroup SocketHeader + * Specific Enumuration-typdefs used for socket operations + * @{ */ + +/*! +@typedef \ + SOCKET + +@brief + Definition for socket handler data type. + Socket ID,used with all socket operations to uniquely identify the socket handler. + Such an ID is uniquely assigned at socket creation when calling @ref socket operation. +*/ +typedef sint8 SOCKET; + +/* FIXME + * the following block conflicts with zephyr's symbols + */ +#ifndef __ZEPHYR__ + +/*! +@struct \ + in_addr + +@brief + IPv4 address representation. + + This structure is used as a placeholder for IPV4 address in other structures. +@see + sockaddr_in +*/ +typedef struct{ + uint32 s_addr; + /*!< + Network Byte Order representation of the IPv4 address. For example, + the address "192.168.0.10" is represented as 0x0A00A8C0. + */ +}in_addr; + + +/*! +@struct \ + sockaddr + +@brief + Generic socket address structure. + +@see \ + sockaddr_in +*/ +struct sockaddr{ + uint16 sa_family; + /*!< +Socket address family. + */ + uint8 sa_data[14]; + /*!< + Maximum size of all the different socket address structures. + */ +}; + + +/*! +@struct \ + sockaddr_in + +@brief + Socket address structure for IPV4 addresses. Used to specify socket address infomation to which to connect to. + Can be cast to @ref sockaddr structure. +*/ +struct sockaddr_in{ + uint16 sin_family; + /*!< + Specifies the address familly(AF). + Members of AF_INET address family are IPv4 addresses. + Hence,the only supported value for this is AF_INET. + */ + uint16 sin_port; + /*!< + Port number of the socket. + Network sockets are identified by a pair of IP addresses and port number. + It must be set in the Network Byte Order format , @ref _htons (e.g. _htons(80)). + Can NOT have zero value. + */ + in_addr sin_addr; + /*!< + IP Address of the socket. + The IP address is of type @ref in_addr structure. + Can be set to "0" to accept any IP address for server operation. non zero otherwise. + */ + uint8 sin_zero[8]; + /*!< + Padding to make structure the same size as @ref sockaddr. + */ +}; +#endif /* __ZEPHYR__ */ + //@} +/**@defgroup AsyncCalback Asynchronous Events + * @ingroup SocketEnums + * Specific Enumuration used for asynchronous operations + * @{ */ +/*! +@enum \ + tenuSocketCallbackMsgType + +@brief + Asynchronous APIs, make use of callback functions, in-order to return back the results once the corresponding socket operation is completed. + Hence resuming the normal execution of the application code while the socket operation returns the results. + Callback functions expect event messages to be passed in, in-order to identify the operation they're returning the results for. + The following enum identifes the type of events that are received in the callback function. + + Application Use: + In order for application developers to handle the pending events from the network controller through the callback functions. + A function call must be made to the function @ref m2m_wifi_handle_events at least once for each socket operation. + +@see + bind + listen + accept + connect + send + recv + +*/ +typedef enum{ + SOCKET_MSG_BIND = 1, + /*!< + Bind socket event. + */ + SOCKET_MSG_LISTEN, + /*!< + Listen socket event. + */ + SOCKET_MSG_DNS_RESOLVE, + /*!< + DNS Resolution event. + */ + SOCKET_MSG_ACCEPT, + /*!< + Accept socket event. + */ + SOCKET_MSG_CONNECT, + /*!< + Connect socket event. + */ + SOCKET_MSG_RECV, + /*!< + Receive socket event. + */ + SOCKET_MSG_SEND, + /*!< + Send socket event. + */ + SOCKET_MSG_SENDTO, + /*!< + sendto socket event. + */ + SOCKET_MSG_RECVFROM + /*!< + Recvfrom socket event. + */ +}tenuSocketCallbackMsgType; + + +/*! +@struct \ + tstrSocketBindMsg + +@brief Socket bind status. + + An asynchronous call to the @ref bind socket operation, returns information through this structure in response. + This structure together with the event @ref SOCKET_MSG_BIND are passed in paramters to the callback function. +@see + bind + +*/ +typedef struct{ + sint8 status; + /*!< + The result of the bind operation. + Holding a value of ZERO for a successful bind or otherwise a negative + error code corresponding to the type of error. + */ +}tstrSocketBindMsg; + + +/*! +@struct \ + tstrSocketListenMsg + +@brief Socket listen status. + + Socket listen information is returned through this structure in response to the asynchronous call to the @ref listen function. + This structure together with the event @ref SOCKET_MSG_LISTEN are passed-in paramters to the callback function. +@see + listen +*/ +typedef struct{ + sint8 status; + /*!< + Holding a value of ZERO for a successful listen or otherwise a negative + error code corresponding to the type of error. + */ +}tstrSocketListenMsg; + + + +/*! +@struct \ + tstrSocketAcceptMsg + +@brief Socket accept status. + + Socket accept information is returned through this structure in response to the asynchronous call to the @ref accept function. + This structure together with the event @ref SOCKET_MSG_ACCEPT are passed-in parameters to the callback function. +*/ +typedef struct{ + SOCKET sock; + /*!< + On a successful @ref accept operation, the return information is the socket ID for the accepted connection with the remote peer. + Otherwise a negative error code is returned to indicate failure of the accept operation. + */ + struct sockaddr_in strAddr; + /*!< + Socket address structure for the remote peer. + */ +}tstrSocketAcceptMsg; + + +/*! +@struct \ + tstrSocketConnectMsg + +@brief Socket connect status. + + Socket connect information is returned through this structure in response to the asynchronous call to the @ref connect socket function. + This structure together with the event @ref SOCKET_MSG_CONNECT are passed-in paramters to the callback function. +*/ +typedef struct{ + SOCKET sock; + /*!< + Socket ID referring to the socket passed to the connect function call. + */ + sint8 s8Error; + /*!< + Connect error code. + Holding a value of ZERO for a successful connect or otherwise a negative + error code corresponding to the type of error. + */ +}tstrSocketConnectMsg; + + +/*! +@struct \ + tstrSocketRecvMsg + +@brief Socket recv status. + + Socket receive information is returned through this structure in response to the asynchronous call to the recv or recvfrom socket functions. + This structure together with the events @ref SOCKET_MSG_RECV or @ref SOCKET_MSG_RECVFROM are passed-in parameters to the callback function. +@remark + In case the received data from the remote peer is larger than the USER buffer size defined during the asynchronous call to the @ref recv function, the data is + delivered to the user in a number of consecutive chunks according to the USER Buffer size. + a negative or zero buffer size indicates an error with the following code: + @ref SOCK_ERR_NO_ERROR : Socket connection closed + @ref SOCK_ERR_CONN_ABORTED : Socket connection aborted + @SOCK_ERR_TIMEOUT : Socket recieve timed out +*/ +typedef struct{ + uint8 *pu8Buffer; + /*!< + Pointer to the USER buffer (passed to @ref recv and @ref recvfrom function) containing the received data chunk. + */ + sint16 s16BufferSize; + /*!< + The recevied data chunk size. + Holds a negative value if there is a receive error or ZERO on success upon reception of close socket message. + */ + uint16 u16RemainingSize; + /*!< + The number of bytes remaining in the current @ref recv operation. + */ + struct sockaddr_in strRemoteAddr; + /*!< + Socket address structure for the remote peer. It is valid for @ref SOCKET_MSG_RECVFROM event. + */ +}tstrSocketRecvMsg; + + +/*! +@typedef \ + tpfAppSocketCb + +@brief + The main socket application callback function. Applications register their main socket application callback through this function by calling @ref registerSocketCallback. + In response to events received, the following callback function is called to handle the corresponding asynchronous function called. Example: @ref bind, @ref connect,...etc. + +@param [in] sock + Socket ID for the callback. + + The socket callback function is called whenever a new event is recived in response + to socket operations. + +@param [in] u8Msg + Socket event type. Possible values are: + - @ref SOCKET_MSG_BIND + - @ref SOCKET_MSG_LISTEN + - @ref SOCKET_MSG_ACCEPT + - @ref SOCKET_MSG_CONNECT + - @ref SOCKET_MSG_RECV + - @ref SOCKET_MSG_SEND + - @ref SOCKET_MSG_SENDTO + - @ref SOCKET_MSG_RECVFROM + +@param [in] pvMsg + Pointer to message structure. Existing types are: + - tstrSocketBindMsg + - tstrSocketListenMsg + - tstrSocketAcceptMsg + - tstrSocketConnectMsg + - tstrSocketRecvMsg + +@see + tenuSocketCallbackMsgType + tstrSocketRecvMsg + tstrSocketConnectMsg + tstrSocketAcceptMsg + tstrSocketListenMsg + tstrSocketBindMsg +*/ +typedef void (*tpfAppSocketCb) (SOCKET sock, uint8 u8Msg, void * pvMsg); + + +/*! +@typedef \ + tpfAppResolveCb + +@brief + DNS resolution callback function. + Applications requiring DNS resolution should register their callback through this function by calling @ref registerSocketCallback. + The following callback is triggered in response to asynchronous call to the @ref gethostbyname function (DNS Resolution callback). + +@param [in] pu8DomainName + Domain name of the host. + +@param [in] u32ServerIP + Server IPv4 address encoded in NW byte order format. If it is Zero, then the DNS resolution failed. +*/ +typedef void (*tpfAppResolveCb) (uint8* pu8DomainName, uint32 u32ServerIP); + +/*! +@typedef \ + tpfPingCb + +@brief PING Callback + + The function delivers the ping statistics for the sent ping triggered by calling + m2m_ping_req. + +@param [in] u32IPAddr + Destination IP. + +@param [in] u32RTT + Round Trip Time. + +@param [in] u8ErrorCode + Ping error code. It may be one of: + - PING_ERR_SUCCESS + - PING_ERR_DEST_UNREACH + - PING_ERR_TIMEOUT +*/ +typedef void (*tpfPingCb)(uint32 u32IPAddr, uint32 u32RTT, uint8 u8ErrorCode); + + /**@}*/ +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ +/** \defgroup SocketAPI Function + * @ingroup SocketHeader + */ + +/** @defgroup SocketInitalizationFn socketInit + * @ingroup SocketAPI + * The function performs the necessary initializations for the socket library through the following steps: + - A check made by the global variable gbSocketInit, ensuring that initialzation for sockets is performed only once, + in-order to prevent reseting the socket instances already created in the global socket array (gastrSockets). + - Zero initializations to the global socket array (gastrSockets), which holds the list of TCP sockets. + - Registers the socket (Host Interface)hif callback function through the call to the hif_register_cb function. + This facilitates handling all of the socket related functions received through interrupts from the firmware. + + */ + /**@{*/ +/*! +@fn \ + NMI_API void socketInit(void); + +@param [in] void + +@return void + +@remarks + This initialization function must be invoked before any socket operation is performed. + No error codes from this initialization function since the socket array is statically allocated based in the maximum number of + sockets @ref MAX_SOCKET based on the systems capibility. +\section Example +This example demonstrates the use of the socketinit for socket initialization for an mqtt chat application. + \code + tstrWifiInitParam param; + int8_t ret; + char topic[strlen(MAIN_CHAT_TOPIC) + MAIN_CHAT_USER_NAME_SIZE + 1]; + + //Initialize the board. + system_init(); + + //Initialize the UART console. + configure_console(); + + // Initialize the BSP. + nm_bsp_init(); + + ---------- + + // Initialize socket interface. + socketInit(); + registerSocketCallback(socket_event_handler, socket_resolve_handler); + + // Connect to router. + m2m_wifi_connect((char *)MAIN_WLAN_SSID, sizeof(MAIN_WLAN_SSID), + MAIN_WLAN_AUTH, (char *)MAIN_WLAN_PSK, M2M_WIFI_CH_ALL); + +\endcode +*/ +NMI_API void socketInit(void); + +/*! +@fn \ + NMI_API void socketDeinit(void); + +@brief Socket Layer De-initialization + + The function performs the necessary cleanup for the socket library static data + It must be invoked as the last any socket operation is performed on any active sockets. +*/ +NMI_API void socketDeinit(void); +/** @} */ +/** @defgroup SocketCallbackFn registerSocketCallback + * @ingroup SocketAPI + Register two callback functions one for asynchronous socket events and the other one for DNS callback registering function. + The registered callback functions are used to retrieve information in response to the asynchronous socket functions called. + */ + /**@{*/ + + +/*! +@fn \ + NMI_API void registerSocketCallback(tpfAppSocketCb socket_cb, tpfAppResolveCb resolve_cb); + +@param [in] tpfAppSocketCb + Assignment of callback function to the global callback @ref tpfAppSocketCb gpfAppSocketCb. Delivers + socket messages to the host application. In response to the asynchronous function calls, such as @ref bind + @ref listen @ref accept @ref connect + +@param [in] tpfAppResolveCb + Assignment of callback function to the global callback @ref tpfAppResolveCb gpfAppResolveCb. + Used for DNS resolving functionalites. The DNS resolving technique is determined by the application + registering the callback. + NULL is assigned when, DNS resolution is not required. + +@return void +@remarks + If any of the socket functionaities is not to be used, NULL is passed in as a parameter. + It must be invoked after socketinit and before other socket layer operations. + +\section Example + This example demonstrates the use of the registerSocketCallback to register a socket callback function with DNS resolution CB set to null + for a simple UDP server example. + \code + tstrWifiInitParam param; + int8_t ret; + struct sockaddr_in addr; + + // Initialize the board + system_init(); + + //Initialize the UART console. + configure_console(); + + // Initialize the BSP. + nm_bsp_init(); + + // Initialize socket address structure. + addr.sin_family = AF_INET; + addr.sin_port = _htons(MAIN_WIFI_M2M_SERVER_PORT); + addr.sin_addr.s_addr = _htonl(MAIN_WIFI_M2M_SERVER_IP); + + // Initialize Wi-Fi parameters structure. + memset((uint8_t *)¶m, 0, sizeof(tstrWifiInitParam)); + + // Initialize Wi-Fi driver with data and status callbacks. + param.pfAppWifiCb = wifi_cb; + ret = m2m_wifi_init(¶m); + if (M2M_SUCCESS != ret) { + printf("main: m2m_wifi_init call error!(%d)\r\n", ret); + while (1) { + } + } + + // Initialize socket module + socketInit(); + registerSocketCallback(socket_cb, NULL); + + // Connect to router. + m2m_wifi_connect((char *)MAIN_WLAN_SSID, sizeof(MAIN_WLAN_SSID), MAIN_WLAN_AUTH, (char *)MAIN_WLAN_PSK, M2M_WIFI_CH_ALL); + \endcode +*/ +NMI_API void registerSocketCallback(tpfAppSocketCb socket_cb, tpfAppResolveCb resolve_cb); +/** @} */ + +/** @defgroup SocketFn socket + * @ingroup SocketAPI + * Synchronous socket allocation function based on the specified socket type. Created sockets are non-blocking and their possible types are either TCP or a UDP sockets. + * The maximum allowed number of TCP sockets is @ref TCP_SOCK_MAX sockets while the maximum number of UDP sockets that can be created simultaneously is @ref UDP_SOCK_MAX sockets. + * +*/ + /**@{*/ +/*! +@fn \ + NMI_API SOCKET socket(uint16 u16Domain, uint8 u8Type, uint8 u8Flags); + + +@param [in] u16Domain + Socket family. The only allowed value is AF_INET (IPv4.0) for TCP/UDP sockets. + +@param [in] u8Type + Socket type. Allowed values are: + - [SOCK_STREAM](@ref SOCK_STREAM) + - [SOCK_DGRAM](@ref SOCK_DGRAM) + +@param [in] u8Flags + Used to specify the socket creation flags. It shall be set to zero for normal TCP/UDP sockets. + If could be SOCKET_FLAGS_SSL if the socket is used for SSL session. The use of the flag + [SOCKET_FLAGS_SSL](@ref SOCKET_FLAGS_SSL) has no meaning in case of UDP sockets. + +@pre + The @ref socketInit function must be called once at the beginning of the application to initialize the socket handler. + before any call to the socket function can be made. + +@see + connect + bind + listen + accept + recv + recvfrom + send + sendto + close + setsockopt + getsockopt + +@return + On successful socket creation, a non-blocking socket type is created and a socket ID is returned + In case of failure the function returns a negative value, identifying one of the socket error codes defined. + For example: @ref SOCK_ERR_INVALID for invalid argument or + @ref SOCK_ERR_MAX_TCP_SOCK if the number of TCP allocated sockets exceeds the number of available sockets. + +@remarks + The socket function must be called apriori any other related socket functions "e.g. send, recv, close ..etc" +\section Example + This example demonstrates the use of the socket function to allocate the socket, returning the socket handler to be used for other +socket operations. Socket creation is dependent on the socket type. +\subsection sub1 UDP example +@code + SOCKET UdpServerSocket = -1; + + UdpServerSocket = socket(AF_INET, SOCK_DGRAM, 0); + +@endcode +\subsection sub2 TCP example +@code + static SOCKET tcp_client_socket = -1; + + tcp_client_socket = socket(AF_INET, SOCK_STREAM, 0)); +@endcode +*/ +NMI_API SOCKET socket(uint16 u16Domain, uint8 u8Type, uint8 u8Flags); +/** @} */ +/** @defgroup BindFn bind + * @ingroup SocketAPI +* Asynchronous bind function associates the provided address and local port to the socket. +* The function can be used with both TCP and UDP sockets it's mandatory to call the @ref bind function before starting any UDP or TCP server operation. +* Upon socket bind completion, the application will receive a @ref SOCKET_MSG_BIND message in the socket callback. +*/ + /**@{*/ +/*! +\fn \ + NMI_API sint8 bind(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen); + + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] pstrAddr + Pointer to socket address structure "sockaddr_in" + [sockaddr_in](@ref sockaddr_in) + + +@param [in] u8AddrLen + Size of the given socket address structure in bytes. + +@pre + The socket function must be called to allocate a socket before passing the socket ID to the bind function. + +@see + socket + connect + listen + accept + recv + recvfrom + send + sendto + +@return + The function returns ZERO for successful operations and a negative value otherwise. + The possible error values are: + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + Indicating that the operation was successful. + + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) + Indicating passing invalid arguments such as negative socket ID or NULL socket address structure. + + - [SOCK_ERR_INVALID](@ref SOCK_ERR_INVALID) + Indicate socket bind failure. +\section Example + This example demonstrates the call of the bind socket operation after a successful socket operation. +@code + struct sockaddr_in addr; + SOCKET udpServerSocket =-1; + int ret = -1; + + if(udpServerSocket == -1) + { + udpServerSocket = socket(AF_INET,SOCK_DGRAM,0); + if(udpServerSocket >= 0) + { + addr.sin_family = AF_INET; + addr.sin_port = _htons(UDP_SERVER_PORT); + addr.sin_addr.s_addr = 0; + ret = bind(udpServerSocket,(struct sockaddr*)&addr,sizeof(addr)); + + if(ret == 0) + printf("Bind success!\n"); + else + { + printf("Bind Failed. Error code = %d\n",ret); + close(udpServerSocket); + } + else + { + printf("UDP Server Socket Creation Failed\n"); + return; + } + } +@endcode +*/ +NMI_API sint8 bind(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen); +/** @} */ + +/** @defgroup ListenFn listen + * @ingroup SocketAPI + * After successful socket binding to an IP address and port on the system, start listening on a passive socket for incoming connections. + The socket must be bound on a local port or the listen operationfails. + Upon the call to the asynchronous listen function, response is received through the event [SOCKET_MSG_BIND](@ref SOCKET_MSG_BIND) + in the socket callback. + A successful listen means the TCP server operation is active. If a connection is accepted, then the application socket callback function is + notified with the new connected socket through the event @ref SOCKET_MSG_ACCEPT. Hence there is no need to call the @ref accept function + after calling @ref listen. + + After a connection is accepted, the user is then required to call the @ref recv to recieve any packets transmitted by the remote host or to recieve notification of socket connection + termination. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 listen(SOCKET sock, uint8 backlog); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] backlog + Not used by the current implementation. + +@pre + The bind function must be called to assign the port number and IP address to the socket before the listen operation. + +@see + bind + accept + recv + recvfrom + send + sendto + +@return + The function returns ZERO for successful operations and a negative value otherwise. + The possible error values are: + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + Indicating that the operation was successful. + + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) + Indicating passing invalid arguments such as negative socket ID. + + - [SOCK_ERR_INVALID](@ref SOCK_ERR_INVALID) + Indicate socket listen failure. +\section Example +This example demonstrates the call of the listen socket operation after a successful socket operation. +@code + static void TCP_Socketcallback(SOCKET sock, uint8 u8Msg, void * pvMsg) + { + int ret =-1; + + switch(u8Msg) + { + case SOCKET_MSG_BIND: + { + tstrSocketBindMsg *pstrBind = (tstrSocketBindMsg*)pvMsg; + if(pstrBind != NULL) + { + if(pstrBind->status == 0) + { + ret = listen(sock, 0); + + if(ret <0) + printf("Listen failure! Error = %d\n",ret); + } + else + { + M2M_ERR("bind Failure!\n"); + close(sock); + } + } + } + break; + + case SOCKET_MSG_LISTEN: + { + + tstrSocketListenMsg *pstrListen = (tstrSocketListenMsg*)pvMsg; + if(pstrListen != NULL) + { + if(pstrListen->status == 0) + { + ret = accept(sock,NULL,0); + } + else + { + M2M_ERR("listen Failure!\n"); + close(sock); + } + } + } + break; + + case SOCKET_MSG_ACCEPT: + { + tstrSocketAcceptMsg *pstrAccept = (tstrSocketAcceptMsg*)pvMsg; + + if(pstrAccept->sock >= 0) + { + TcpNotificationSocket = pstrAccept->sock; + recv(pstrAccept->sock,gau8RxBuffer,sizeof(gau8RxBuffer),TEST_RECV_TIMEOUT); + } + else + { + M2M_ERR("accept failure\n"); + } + } + break; + + default: + break; + } + } + +@endcode +*/ +NMI_API sint8 listen(SOCKET sock, uint8 backlog); +/** @} */ +/** @defgroup AcceptFn accept + * @ingroup SocketAPI + * The function has no current implementation. An empty deceleration is used to prevent errors when legacy application code is used. + * For recent application use, the accept function can be saferIt has no effect and could be safely removed from any application using it. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 accept(SOCKET sock, struct sockaddr *addr, uint8 *addrlen); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. +@param [in] addr + Not used in the current implementation. + +@param [in] addrlen + Not used in the current implementation. + +@return + The function returns ZERO for successful operations and a negative value otherwise. + The possible error values are: + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + Indicating that the operation was successful. + + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) + Indicating passing invalid arguments such as negative socket ID. +*/ +NMI_API sint8 accept(SOCKET sock, struct sockaddr *addr, uint8 *addrlen); +/** @} */ +/** @defgroup ConnectFn connect + * @ingroup SocketAPI + * Establishes a TCP connection with a remote server. + The asynchronous connect function must be called after receiving a valid socket ID from the @ref socket function. + The application socket callback function is notified of a successful new socket connection through the event @ref SOCKET_MSG_CONNECT. + A successful connect means the TCP session is active. The application is then required to make a call to the @ref recv + to recieve any packets transmitted by the remote server, unless the application is interrupted by a notification of socket connection + termination. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 connect(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] pstrAddr + Address of the remote server. +@param [in] pstrAddr + Pointer to socket address structure "sockaddr_in" + [sockaddr_in](@ref sockaddr_in) + +@param [in] u8AddrLen + Size of the given socket address structure in bytes. + Not currently used, implemented for BSD compatibility only. +@pre + The socket function must be called to allocate a TCP socket before passing the socket ID to the bind function. + If the socket is not bound, you do NOT have to call bind before the "connect" function. + +@see + socket + recv + send + close + +@return + The function returns ZERO for successful operations and a negative value otherwise. + The possible error values are: + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + Indicating that the operation was successful. + + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) + Indicating passing invalid arguments such as negative socket ID or NULL socket address structure. + + - [SOCK_ERR_INVALID](@ref SOCK_ERR_INVALID) + Indicate socket connect failure. +\section Example + The example demonstrates a TCP application, showing how the asynchronous call to the connect function is made through the main function and how the + callback function handles the @ref SOCKET_MSG_CONNECT event. +\subsection sub1 Main Function +@code + struct sockaddr_in Serv_Addr; + SOCKET TcpClientSocket =-1; + int ret = -1 + + TcpClientSocket = socket(AF_INET,SOCK_STREAM,0); + Serv_Addr.sin_family = AF_INET; + Serv_Addr.sin_port = _htons(1234); + Serv_Addr.sin_addr.s_addr = inet_addr(SERVER); + printf("Connected to server via socket %u\n",TcpClientSocket); + + do + { + ret = connect(TcpClientSocket,(sockaddr_in*)&Serv_Addr,sizeof(Serv_Addr)); + if(ret != 0) + { + printf("Connection Error\n"); + } + else + { + printf("Connection successful.\n"); + break; + } + }while(1) +@endcode +\subsection sub2 Socket Callback +@code + if(u8Msg == SOCKET_MSG_CONNECT) + { + tstrSocketConnectMsg *pstrConnect = (tstrSocketConnectMsg*)pvMsg; + if(pstrConnect->s8Error == 0) + { + uint8 acBuffer[GROWL_MSG_SIZE]; + uint16 u16MsgSize; + + printf("Connect success!\n"); + + u16MsgSize = FormatMsg(u8ClientID, acBuffer); + send(sock, acBuffer, u16MsgSize, 0); + recv(pstrNotification->Socket, (void*)au8Msg,GROWL_DESCRIPTION_MAX_LENGTH, GROWL_RX_TIMEOUT); + u8Retry = GROWL_CONNECT_RETRY; + } + else + { + M2M_DBG("Connection Failed, Error: %d\n",pstrConnect->s8Error"); + close(pstrNotification->Socket); + } + } +@endcode +*/ +NMI_API sint8 connect(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen); +/** @} */ +/** @defgroup ReceiveFn recv + * @ingroup SocketAPI + * An asynchrnonous receive function, used to retrieve data from a TCP stream. + Before calling the recv function, a successful socket connection status must have been received through any of the two socket events + [SOCKET_MSG_CONNECT] or [SOCKET_MSG_ACCEPT], from the socket callback. Hence, indicating that the socket is already connected to a remote + host. + The application receives the required data in response to this asynchronous call through the reception of the event @ref SOCKET_MSG_RECV in the + socket callback. + + Recieving the SOCKET_MSG_RECV message in the callback with zero or negative buffer length indicates the following: + - SOCK_ERR_NO_ERROR : Socket connection closed + - SOCK_ERR_CONN_ABORTED : Socket connection aborted + - SOCK_ERR_TIMEOUT : Socket recieve timed out + The application code is expected to close the socket through the call to the @ref close function upon the appearance of the above mentioned errors. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint16 recv(SOCKET sock, void *pvRecvBuf, uint16 u16BufLen, uint32 u32Timeoutmsec); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + + +@param [in] pvRecvBuf + Pointer to a buffer that will hold the received data. The buffer is used + in the recv callback to deliver the received data to the caller. The buffer must + be resident in memory (heap or global buffer). + +@param [in] u16BufLen + The buffer size in bytes. + +@param [in] u32Timeoutmsec + Timeout for the recv function in milli-seconds. If the value is set to ZERO, the timeout + will be set to infinite (the recv function waits forever). If the timeout period is + elapsed with no data received, the socket will get a timeout error. +@pre + - The socket function must be called to allocate a TCP socket before passing the socket ID to the recv function. + - The socket in a connected state is expected to receive data through the socket interface. + +@see + socket + connect + bind + listen + recvfrom + close + + +@return + The function returns ZERO for successful operations and a negative value otherwise. + The possible error values are: + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + Indicating that the operation was successful. + + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) + Indicating passing invalid arguments such as negative socket ID or NULL Recieve buffer. + + - [SOCK_ERR_BUFFER_FULL](@ref SOCK_ERR_BUFFER_FULL) + Indicate socket recieve failure. +\section Example + The example demonstrates a code snippet for the calling of the recv function in the socket callback upon notification of the accept or connect events, and the parsing of the + received data when the SOCKET_MSG_RECV event is received. +@code + + switch(u8Msg) + { + + case SOCKET_MSG_ACCEPT: + { + tstrSocketAcceptMsg *pstrAccept = (tstrSocketAcceptMsg*)pvMsg; + + if(pstrAccept->sock >= 0) + { + recv(pstrAccept->sock,gau8RxBuffer,sizeof(gau8RxBuffer),TEST_RECV_TIMEOUT); + } + else + { + M2M_ERR("accept\n"); + } + } + break; + + + case SOCKET_MSG_RECV: + { + tstrSocketRecvMsg *pstrRx = (tstrSocketRecvMsg*)pvMsg; + + if(pstrRx->s16BufferSize > 0) + { + + recv(sock,gau8RxBuffer,sizeof(gau8RxBuffer),TEST_RECV_TIMEOUT); + } + else + { + printf("Socet recv Error: %d\n",pstrRx->s16BufferSize); + close(sock); + } + } + break; + + default: + break; + } +} +@endcode +*/ +NMI_API sint16 recv(SOCKET sock, void *pvRecvBuf, uint16 u16BufLen, uint32 u32Timeoutmsec); +/** @} */ +/** @defgroup ReceiveFromSocketFn recvfrom + * @ingroup SocketAPI + * Recieves data from a UDP Scoket. +* +* The asynchronous recvfrom function is used to retrieve data from a UDP socket. The socket must already be bound to +* a local port before a call to the recvfrom function is made (i.e message @ref SOCKET_MSG_BIND is recieved +* with successful status in the socket callback). +* +* Upon calling the recvfrom function with a successful return code, the application is expected to receive a notification +* in the socket callback whenever a message is recieved through the @ref SOCKET_MSG_RECVFROM event. +* +* Receiving the SOCKET_MSG_RECVFROM message in the callback with zero, indicates that the socket is closed. +* Whereby a negative buffer length indicates one of the socket error codes such as socket timeout error @SOCK_ERR_TIMEOUT: +* +* The recvfrom callback can also be used to show the IP address of the remote host that sent the frame by +* using the "strRemoteAddr" element in the @ref tstrSocketRecvMsg structure. (refer to the code example) + */ + /**@{*/ +/*! +@fn \ + NMI_API sint16 recvfrom(SOCKET sock, void *pvRecvBuf, uint16 u16BufLen, uint32 u32TimeoutSeconds); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] pvRecvBuf + Pointer to a buffer that will hold the received data. The buffer shall be used + in the recv callback to deliver the received data to the caller. The buffer must + be resident in memory (heap or global buffer). + +@param [in] u16BufLen + The buffer size in bytes. + +@param [in] u32TimeoutSeconds + Timeout for the recv function in milli-seconds. If the value is set to ZERO, the timeout + will be set to infinite (the recv function waits forever). + +@pre + - The socket function must be called to allocate a TCP socket before passing the socket ID to the recv function. + - The socket corresponding to the socket ID must be successfully bound to a local port through the call to a @ref bind function. + +@see + socket + bind + close + +@return + The function returns ZERO for successful operations and a negative value otherwise. + The possible error values are: + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + Indicating that the operation was successful. + + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) + Indicating passing invalid arguments such as negative socket ID or NULL Recieve buffer. + + - [SOCK_ERR_BUFFER_FULL](@ref SOCK_ERR_BUFFER_FULL) + Indicate socket recieve failure. +\section Example + The example demonstrates a code snippet for the calling of the recvfrom function in the socket callback upon notification of a successful bind event, and the parsing of the + received data when the SOCKET_MSG_RECVFROM event is received. +@code + switch(u8Msg) + { + + case SOCKET_MSG_BIND: + { + tstrSocketBindMsg *pstrBind = (tstrSocketBindMsg*)pvMsg; + + if(pstrBind != NULL) + { + if(pstrBind->status == 0) + { + recvfrom(sock, gau8SocketTestBuffer, TEST_BUFFER_SIZE, 0); + } + else + { + M2M_ERR("bind\n"); + } + } + } + break; + + + case SOCKET_MSG_RECVFROM: + { + tstrSocketRecvMsg *pstrRx = (tstrSocketRecvMsg*)pvMsg; + + if(pstrRx->s16BufferSize > 0) + { + //get the remote host address and port number + uint16 u16port = pstrRx->strRemoteAddr.sin_port; + uint32 strRemoteHostAddr = pstrRx->strRemoteAddr.sin_addr.s_addr; + + printf("Recieved frame with size = %d.\tHost address=%x, Port number = %d\n\n",pstrRx->s16BufferSize,strRemoteHostAddr, u16port); + + ret = recvfrom(sock,gau8SocketTestBuffer,sizeof(gau8SocketTestBuffer),TEST_RECV_TIMEOUT); + } + else + { + printf("Socet recv Error: %d\n",pstrRx->s16BufferSize); + ret = close(sock); + } + } + break; + + default: + break; + } +} +@endcode +*/ +NMI_API sint16 recvfrom(SOCKET sock, void *pvRecvBuf, uint16 u16BufLen, uint32 u32Timeoutmsec); +/** @} */ +/** @defgroup SendFn send + * @ingroup SocketAPI +* Asynchronous sending function, used to send data on a TCP/UDP socket. + +* Called by the application code when there is outgoing data available required to be sent on a specific socket handler. +* The only difference between this function and the similar @ref sendto function, is the type of socket the data is sent on and the parameters passed in. +* @ref send function is most commonly called for sockets in a connected state. +* After the data is sent, the socket callback function registered using registerSocketCallback(), is expected to receive an event of type +* @ref SOCKET_MSG_SEND holding information containing the number of data bytes sent. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint16 send(SOCKET sock, void *pvSendBuffer, uint16 u16SendLength, uint16 u16Flags); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] pvSendBuffer + Pointer to a buffer holding data to be transmitted. + +@param [in] u16SendLength + The buffer size in bytes. + +@param [in] u16Flags + Not used in the current implementation. + +@pre + Sockets must be initialized using socketInit. \n + + For TCP Socket:\n + Must use a successfully connected Socket (so that the intended recipient address is known ahead of sending the data). + Hence this function is expected to be called after a successful socket connect operation(in client case or accept in the + the server case).\n + + For UDP Socket:\n + UDP sockets most commonly use @ref sendto function, where the destination address is defined. However, in-order to send outgoing data + using the @ref send function, atleast one successful call must be made to the @ref sendto function apriori the consecutive calls to the @ref send function, + to ensure that the destination address is saved in the firmware. + +@see + socketInit + recv + sendto + socket + connect + accept + sendto + +@warning + u16SendLength must not exceed @ref SOCKET_BUFFER_MAX_LENGTH. \n + Use a valid socket identifer through the aprior call to the @ref socket function. + Must use a valid buffer pointer. + Successful completion of a call to send() does not guarantee delivery of the message, + A negative return value indicates only locally-detected errors + + +@return + The function shall return @ref SOCK_ERR_NO_ERROR for successful operation and a negative value (indicating the error) otherwise. +*/ +NMI_API sint16 send(SOCKET sock, void *pvSendBuffer, uint16 u16SendLength, uint16 u16Flags); +/** @} */ +/** @defgroup SendToSocketFn sendto + * @ingroup SocketAPI +* Asynchronous sending function, used to send data on a UDP socket. +* Called by the application code when there is data required to be sent on a UDP socket handler. +* The application code is expected to receive data from a successful bounded socket node. +* The only difference between this function and the similar @ref send function, is the type of socket the data is received on. This function works +* only with UDP sockets. +* After the data is sent, the socket callback function registered using registerSocketCallback(), is expected to receive an event of type +* @ref SOCKET_MSG_SENDTO. +*/ + /**@{*/ +/*! +@fn \ + NMI_API sint16 sendto(SOCKET sock, void *pvSendBuffer, uint16 u16SendLength, uint16 flags, struct sockaddr *pstrDestAddr, uint8 u8AddrLen); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] pvSendBuffer + Pointer to a buffer holding data to be transmitted. + A NULL value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@param [in] u16SendLength + The buffer size in bytes. It must not exceed @ref SOCKET_BUFFER_MAX_LENGTH. + +@param [in] flags + Not used in the current implementation + +@param [in] pstrDestAddr + The destination address. + +@param [in] u8AddrLen + Destination address length in bytes. + Not used in the current implementation, only included for BSD compatibility. +@pre + Sockets must be initialized using socketInit. + +@see + socketInit + recvfrom + sendto + socket + connect + accept + send + +@warning + u16SendLength must not exceed @ref SOCKET_BUFFER_MAX_LENGTH. \n + Use a valid socket (returned from socket ). + A valid buffer pointer must be used (not NULL). \n + Successful completion of a call to sendto() does not guarantee delivery of the message, + A negative return value indicates only locally-detected errors + +@return + The function returns @ref SOCK_ERR_NO_ERROR for successful operation and a negative value (indicating the error) otherwise. +*/ +NMI_API sint16 sendto(SOCKET sock, void *pvSendBuffer, uint16 u16SendLength, uint16 flags, struct sockaddr *pstrDestAddr, uint8 u8AddrLen); +/** @} */ +/** @defgroup CloseSocketFn close + * @ingroup SocketAPI + * Synchronous close function, releases all the socket assigned resources. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 close(SOCKET sock); + +@param [in] sock + Socket ID, must hold a non negative value. + A negative value will return a socket error @ref SOCK_ERR_INVALID_ARG. Indicating that an invalid argument is passed in. + +@pre + Sockets must be initialized through the call of the socketInit function. + @ref close is called only for valid socket identifers created through the @ref socket function. + +@warning + If @ref close is called while there are still pending messages (sent or received ) they will be discarded. + +@see + socketInit + socket + +@return + The function returned @ref SOCK_ERR_NO_ERROR for successful operation and a negative value (indicating the error) otherwise. +*/ +NMI_API sint8 close(SOCKET sock); +/** @} */ +/** @defgroup InetAddressFn nmi_inet_addr +* @ingroup SocketAPI +* Synchronous function which returns a BSD socket compliant Internet Protocol (IPv4) socket address. +* This IPv4 address in the input string parameter could either be specified as a hostname, or as a numeric string representation like n.n.n.n known as the IPv4 dotted-decimal format +* (i.e. "192.168.10.1"). +* This function is used whenever an ip address needs to be set in the proper format +* (i.e. for the @ref tstrM2MIPConfig structure). +*/ + /**@{*/ +/*! +@fn \ + NMI_API uint32 nmi_inet_addr(char *pcIpAddr); + +@param [in] pcIpAddr + A null terminated string containing the IP address in IPv4 dotted-decimal address. + +@return + Unsigned 32-bit integer representing the IP address in Network byte order + (eg. "192.168.10.1" will be expressed as 0x010AA8C0). + +*/ +NMI_API uint32 nmi_inet_addr(char *pcIpAddr); +/** @} */ +/** @defgroup gethostbynameFn gethostbyname + * @ingroup SocketAPI +* Asynchronous DNS resolving function. This function use DNS to resolve a domain name into the corresponding IP address. +* A call to this function will cause a DNS request to be sent and the response will be delivered to the DNS callback function registered using registerSocketCallback() + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 gethostbyname(uint8 * pcHostName); + +@param [in] pcHostName + NULL terminated string containing the domain name for the remote host. + Its size must not exceed [HOSTNAME_MAX_SIZE](@ref HOSTNAME_MAX_SIZE). + +@see + registerSocketCallback + +@warning + Successful completion of a call to gethostbyname() does not guarantee success of the DNS request, + a negative return value indicates only locally-detected errors + +@return + - [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) + - [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) +*/ +NMI_API sint8 gethostbyname(uint8 * pcHostName); + + + +/** @} */ +/** @defgroup sslSetActiveCipherSuitesFn sslSetActiveCipherSuites + * @ingroup SocketAPI + * Overrides the default active SSL ciphers in the SSL module with a certain combination of ciphers selected by the caller using + * a bitmap containing the required ciphers list. + * There API is required only if the will not change the default ciphersuites, otherwise, it is not recommended to use. + */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 sslSetActiveCipherSuites(uint32 u32SslCsBMP); + +@param [in] u32SslCsBMP +

A non-zero 32-bit integer bitmap containing the bitwise OR of the desired ciphers to be enabled +for the SSL module. The ciphersuites are defined in groups as follows:

+
    +
  • @ref SSL_ENABLE_ALL_SUITES
  • +
  • @ref SSL_ENABLE_RSA_SHA_SUITES
  • +
  • @ref SSL_ENABLE_RSA_SHA256_SUITES
  • +
  • @ref SSL_ENABLE_DHE_SHA_SUITES
  • +
  • @ref SSL_ENABLE_DHE_SHA256_SUITES
  • +
  • @ref SSL_ENABLE_RSA_GCM_SUITES
  • +
  • @ref SSL_ENABLE_DHE_GCM_SUITES
  • +
+@return + Possible return values are [SOCK_ERR_NO_ERROR](@ref SOCK_ERR_NO_ERROR) if case of success + or [SOCK_ERR_INVALID_ARG](@ref SOCK_ERR_INVALID_ARG) if the map is zero. +@remarks +The default supported ciphersuites are the combination of all the above groups. The caller can override the default with any desired combination. +For example, to disable SHA based ciphers the function should be called with this syntax: +\code + sslSetActiveCipherSuites(SSL_ENABLE_ALL_SUITES & ~(SSL_ENABLE_RSA_SHA_SUITES|SSL_ENABLE_DHE_SHA_SUITES)); +\endcode +@note Passing the u32SslCsBMP as zero will not change the current active list. +*/ +NMI_API sint8 sslSetActiveCipherSuites(uint32 u32SslCsBMP); + + +/** @} */ + +/** @defgroup SetSocketOptionFn setsockopt + * @ingroup SocketAPI +*The setsockopt() function shall set the option specified by the option_name +* argument, at the protocol level specified by the level argument, to the value +* pointed to by the option_value argument for the socke specified by the socket argument. +* +*

Possible protcol level values supported are @ref SOL_SOCKET and @ref SOL_SSL_SOCKET. +* Possible options when the protocol level is @ref SOL_SOCKET :

+* +* +* +* +* +* +* +* +* +* +* +* +* +*
@ref SO_SET_UDP_SEND_CALLBACKEnable/Disable callback messages for sendto(). +* Since UDP is unreliable by default the user maybe interested (or not) in +* receiving a message of @ref SOCKET_MSG_SENDTO for each call of sendto(). +* Enabled if option value equals @ref TRUE, disabled otherwise.
@ref IP_ADD_MEMBERSHIPValid for UDP sockets. This option is used to receive frames sent to +* a multicast group. option_value shall be a pointer to Unsigned 32-bit +* integer containing the multicast IPv4 address.
@ref IP_DROP_MEMBERSHIPValid for UDP sockets. This option is used to stop receiving frames +* sent to a multicast group. option_value shall be a pointer to Unsigned +* 32-bit integer containing the multicast IPv4 address.
+*

Possible options when the protcol leve  is @ref SOL_SSL_SOCKET

+* +* +* +* +* +* +* +* +* +* +* +* +* +*
+* @ref SO_SSL_BYPASS_X509_VERIFAllow an opened SSL socket to bypass the X509 +* certificate verification process. It is highly recommended NOT to use +* this socket option in production software applications. The option is +* supported for debugging and testing purposes. The option value should be +* casted to int type and it is handled as a boolean flag.
@ref SO_SSL_SNISet the Server Name Indicator (SNI) for an SSL socket. The SNI is a +* null terminated string containing the server name assocated with the +* connection. It must not exceed the size of @ref HOSTNAME_MAX_SIZE.
@ref SO_SSL_ENABLE_SESSION_CACHINGThis option allow the TLS to cache the session information for fast +* TLS session establishment in future connections using the TLS Protocol +* session resume features.
+ */ + /**@{*/ +/*! +@fn \ + NMI_API sint8 setsockopt(SOCKET socket, uint8 u8Level, uint8 option_name, + const void *option_value, uint16 u16OptionLen); + +@param [in] sock + Socket handler. + +@param [in] level + protocol level. See description above. + +@param [in] option_name + option to be set. See description above. + +@param [in] option_value + pointer to user provided value. + +@param [in] option_len + length of the option value in bytes. +@return + The function shall return \ref SOCK_ERR_NO_ERROR for successful operation + and a negative value (indicating the error) otherwise. +@sa SOL_SOCKET, SOL_SSL_SOCKET, +*/ +NMI_API sint8 setsockopt(SOCKET socket, uint8 u8Level, uint8 option_name, + const void *option_value, uint16 u16OptionLen); + + +/** @} */ +/** @defgroup GetSocketOptionsFn getsockopt + * @ingroup SocketAPI + * Get socket options retrieves +* This Function isn't implemented yet but this is the form that will be released later. + */ + /**@{*/ +/*! +@fn \ + sint8 getsockopt(SOCKET sock, uint8 u8Level, uint8 u8OptName, const void *pvOptValue, uint8 * pu8OptLen); + +@brief + + +@param [in] sock + Socket Identifie. +@param [in] u8Level + The protocol level of the option. +@param [in] u8OptName + The u8OptName argument specifies a single option to get. +@param [out] pvOptValue + The pvOptValue argument contains pointer to a buffer containing the option value. +@param [out] pu8OptLen + Option value buffer length. +@return + The function shall return ZERO for successful operation and a negative value otherwise. +*/ +NMI_API sint8 getsockopt(SOCKET sock, uint8 u8Level, uint8 u8OptName, const void *pvOptValue, uint8* pu8OptLen); +/** @} */ + +/**@}*/ +/** @defgroup PingFn m2m_ping_req + * @ingroup SocketAPI + * The function request to send ping request to the given IP Address. + */ + /**@{*/ +/*! + * @fn NMI_API sint8 m2m_ping_req(uint32 u32DstIP, uint8 u8TTL); + * @param [in] u32DstIP + * Target Destination IP Address for the ping request. It must be represented in Network + * byte order. + * The function nmi_inet_addr could be used to translate the dotted decimal notation IP + * to its Network bytes order integer represntative. + * + * @param [in] u8TTL + * IP TTL value for the ping request. If set to ZERO, the dfault value SHALL be used. + * + * @param [in] fpPingCb + * Callback will be called to deliver the ping statistics. + * + * @see nmi_inet_addr + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +NMI_API sint8 m2m_ping_req(uint32 u32DstIP, uint8 u8TTL, tpfPingCb fpPingCb); +/**@}*/ + + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* __SOCKET_H__ */ + diff --git a/ext/drivers/atmel/winc1500/socket/source/socket.c b/ext/drivers/atmel/winc1500/socket/source/socket.c new file mode 100644 index 0000000000000..75c013e835740 --- /dev/null +++ b/ext/drivers/atmel/winc1500/socket/source/socket.c @@ -0,0 +1,1274 @@ +/** + * + * \file + * + * \brief BSD alike socket interface. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "bsp/include/nm_bsp.h" +#include "socket/include/socket.h" +#include "driver/source/m2m_hif.h" +#include "socket/source/socket_internal.h" +#include "driver/include/m2m_types.h" + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +MACROS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +#define TLS_RECORD_HEADER_LENGTH (5) +#define ETHERNET_HEADER_OFFSET (34) +#define ETHERNET_HEADER_LENGTH (14) +#define TCP_IP_HEADER_LENGTH (40) +#define UDP_IP_HEADER_LENGTH (28) + +#define IP_PACKET_OFFSET (ETHERNET_HEADER_LENGTH + ETHERNET_HEADER_OFFSET - M2M_HIF_HDR_OFFSET) + +#define TCP_TX_PACKET_OFFSET (IP_PACKET_OFFSET + TCP_IP_HEADER_LENGTH) +#define UDP_TX_PACKET_OFFSET (IP_PACKET_OFFSET + UDP_IP_HEADER_LENGTH) +#define SSL_TX_PACKET_OFFSET (TCP_TX_PACKET_OFFSET + TLS_RECORD_HEADER_LENGTH) + +#define SOCKET_REQUEST(reqID, reqArgs, reqSize, reqPayload, reqPayloadSize, reqPayloadOffset) \ + hif_send(M2M_REQ_GROUP_IP, reqID, reqArgs, reqSize, reqPayload, reqPayloadSize, reqPayloadOffset) + + +#define SSL_FLAGS_ACTIVE NBIT0 +#define SSL_FLAGS_BYPASS_X509 NBIT1 +#define SSL_FLAGS_2_RESERVD NBIT2 +#define SSL_FLAGS_3_RESERVD NBIT3 +#define SSL_FLAGS_CACHE_SESSION NBIT4 +#define SSL_FLAGS_NO_TX_COPY NBIT5 + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +PRIVATE DATA TYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + + +/*! +* @brief +*/ +typedef struct{ + SOCKET sock; + uint8 u8Dummy; + uint16 u16SessionID; +}tstrCloseCmd; + + +/*! +* @brief +*/ +typedef struct{ + uint8 *pu8UserBuffer; + uint16 u16UserBufferSize; + uint16 u16SessionID; + uint16 u16DataOffset; + uint8 bIsUsed; + uint8 u8SSLFlags; + uint8 bIsRecvPending; +}tstrSocket; + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +GLOBALS +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +volatile sint8 gsockerrno; +volatile tstrSocket gastrSockets[MAX_SOCKET]; +volatile uint8 gu8OpCode; +volatile uint16 gu16BufferSize; +volatile uint16 gu16SessionID = 0; + +volatile tpfAppSocketCb gpfAppSocketCb; +volatile tpfAppResolveCb gpfAppResolveCb; +volatile uint8 gbSocketInit = 0; +volatile tpfPingCb gfpPingCb; + +/********************************************************************* +Function + Socket_ReadSocketData + +Description + Callback function used by the NMC1500 driver to deliver messages + for socket layer. + +Return + None. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 17 July 2012 +*********************************************************************/ +NMI_API void Socket_ReadSocketData(SOCKET sock, tstrSocketRecvMsg *pstrRecv,uint8 u8SocketMsg, + uint32 u32StartAddress,uint16 u16ReadCount) +{ + if((u16ReadCount > 0) && (gastrSockets[sock].pu8UserBuffer != NULL) && (gastrSockets[sock].u16UserBufferSize > 0) && (gastrSockets[sock].bIsUsed == 1)) + { + uint32 u32Address = u32StartAddress; + uint16 u16Read; + sint16 s16Diff; + uint8 u8SetRxDone; + + pstrRecv->u16RemainingSize = u16ReadCount; + do + { + u8SetRxDone = 1; + u16Read = u16ReadCount; + s16Diff = u16Read - gastrSockets[sock].u16UserBufferSize; + if(s16Diff > 0) + { + u8SetRxDone = 0; + u16Read = gastrSockets[sock].u16UserBufferSize; + } + if(hif_receive(u32Address, gastrSockets[sock].pu8UserBuffer, u16Read, u8SetRxDone) == M2M_SUCCESS) + { + pstrRecv->pu8Buffer = gastrSockets[sock].pu8UserBuffer; + pstrRecv->s16BufferSize = u16Read; + pstrRecv->u16RemainingSize -= u16Read; + + if (gpfAppSocketCb) + gpfAppSocketCb(sock,u8SocketMsg, pstrRecv); + + u16ReadCount -= u16Read; + u32Address += u16Read; + } + else + { + M2M_INFO("(ERRR)Current <%d>\n", u16ReadCount); + break; + } + }while(u16ReadCount != 0); + } +} +/********************************************************************* +Function + m2m_ip_cb + +Description + Callback function used by the NMC1000 driver to deliver messages + for socket layer. + +Return + None. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 17 July 2012 +*********************************************************************/ +static void m2m_ip_cb(uint8 u8OpCode, uint16 u16BufferSize,uint32 u32Address) +{ + if(u8OpCode == SOCKET_CMD_BIND) + { + tstrBindReply strBindReply; + tstrSocketBindMsg strBind; + + if(hif_receive(u32Address, (uint8*)&strBindReply, sizeof(tstrBindReply), 0) == M2M_SUCCESS) + { + strBind.status = strBindReply.s8Status; + if(gpfAppSocketCb) + gpfAppSocketCb(strBindReply.sock,SOCKET_MSG_BIND,&strBind); + } + } + else if(u8OpCode == SOCKET_CMD_LISTEN) + { + tstrListenReply strListenReply; + tstrSocketListenMsg strListen; + if(hif_receive(u32Address, (uint8*)&strListenReply, sizeof(tstrListenReply), 0) == M2M_SUCCESS) + { + strListen.status = strListenReply.s8Status; + if(gpfAppSocketCb) + gpfAppSocketCb(strListenReply.sock,SOCKET_MSG_LISTEN, &strListen); + } + } + else if(u8OpCode == SOCKET_CMD_ACCEPT) + { + tstrAcceptReply strAcceptReply; + tstrSocketAcceptMsg strAccept; + if(hif_receive(u32Address, (uint8*)&strAcceptReply, sizeof(tstrAcceptReply), 0) == M2M_SUCCESS) + { + if(strAcceptReply.sConnectedSock >= 0) + { + gastrSockets[strAcceptReply.sConnectedSock].u8SSLFlags = 0; + gastrSockets[strAcceptReply.sConnectedSock].bIsUsed = 1; + + /* The session ID is used to distinguish different socket connections + by comparing the assigned session ID to the one reported by the firmware*/ + ++gu16SessionID; + if(gu16SessionID == 0) + ++gu16SessionID; + + gastrSockets[strAcceptReply.sConnectedSock].u16SessionID = gu16SessionID; + M2M_DBG("Socket %d session ID = %d\r\n",strAcceptReply.sConnectedSock , gu16SessionID ); + } + strAccept.sock = strAcceptReply.sConnectedSock; + strAccept.strAddr.sin_family = AF_INET; + strAccept.strAddr.sin_port = strAcceptReply.strAddr.u16Port; + strAccept.strAddr.sin_addr.s_addr = strAcceptReply.strAddr.u32IPAddr; + if(gpfAppSocketCb) + gpfAppSocketCb(strAcceptReply.sListenSock, SOCKET_MSG_ACCEPT, &strAccept); + } + } + else if((u8OpCode == SOCKET_CMD_CONNECT) || (u8OpCode == SOCKET_CMD_SSL_CONNECT)) + { + tstrConnectReply strConnectReply; + tstrSocketConnectMsg strConnMsg; + if(hif_receive(u32Address, (uint8*)&strConnectReply, sizeof(tstrConnectReply), 0) == M2M_SUCCESS) + { + strConnMsg.sock = strConnectReply.sock; + strConnMsg.s8Error = strConnectReply.s8Error; + if(strConnectReply.s8Error == SOCK_ERR_NO_ERROR) + { + gastrSockets[strConnectReply.sock].u16DataOffset = strConnectReply.u16AppDataOffset - M2M_HIF_HDR_OFFSET; + } + if(gpfAppSocketCb) + gpfAppSocketCb(strConnectReply.sock,SOCKET_MSG_CONNECT, &strConnMsg); + } + } + else if(u8OpCode == SOCKET_CMD_DNS_RESOLVE) + { + tstrDnsReply strDnsReply; + if(hif_receive(u32Address, (uint8*)&strDnsReply, sizeof(tstrDnsReply), 0) == M2M_SUCCESS) + { + strDnsReply.u32HostIP = strDnsReply.u32HostIP; + if(gpfAppResolveCb) + gpfAppResolveCb((uint8*)strDnsReply.acHostName, strDnsReply.u32HostIP); + } + } + else if((u8OpCode == SOCKET_CMD_RECV) || (u8OpCode == SOCKET_CMD_RECVFROM) || (u8OpCode == SOCKET_CMD_SSL_RECV)) + { + SOCKET sock; + sint16 s16RecvStatus; + tstrRecvReply strRecvReply; + uint16 u16ReadSize; + tstrSocketRecvMsg strRecvMsg; + uint8 u8CallbackMsgID = SOCKET_MSG_RECV; + uint16 u16DataOffset; + + if(u8OpCode == SOCKET_CMD_RECVFROM) + u8CallbackMsgID = SOCKET_MSG_RECVFROM; + + /* Read RECV REPLY data structure. + */ + u16ReadSize = sizeof(tstrRecvReply); + if(hif_receive(u32Address, (uint8*)&strRecvReply, u16ReadSize, 0) == M2M_SUCCESS) + { + uint16 u16SessionID = 0; + + sock = strRecvReply.sock; + u16SessionID = strRecvReply.u16SessionID; + M2M_DBG("recv callback session ID = %d\r\n",u16SessionID); + + /* Reset the Socket RX Pending Flag. + */ + gastrSockets[sock].bIsRecvPending = 0; + + s16RecvStatus = NM_BSP_B_L_16(strRecvReply.s16RecvStatus); + u16DataOffset = NM_BSP_B_L_16(strRecvReply.u16DataOffset); + strRecvMsg.strRemoteAddr.sin_port = strRecvReply.strRemoteAddr.u16Port; + strRecvMsg.strRemoteAddr.sin_addr.s_addr = strRecvReply.strRemoteAddr.u32IPAddr; + if(u16SessionID == gastrSockets[sock].u16SessionID) + { + if((s16RecvStatus > 0) && (s16RecvStatus < u16BufferSize)) + { + /* Skip incoming bytes until reaching the Start of Application Data. + */ + u32Address += u16DataOffset; + + /* Read the Application data and deliver it to the application callback in + the given application buffer. If the buffer is smaller than the received data, + the data is passed to the application in chunks according to its buffer size. + */ + u16ReadSize = (uint16)s16RecvStatus; + Socket_ReadSocketData(sock, &strRecvMsg, u8CallbackMsgID, u32Address, u16ReadSize); + } + else + { + strRecvMsg.s16BufferSize = s16RecvStatus; + strRecvMsg.pu8Buffer = NULL; + if(gpfAppSocketCb) + gpfAppSocketCb(sock,u8CallbackMsgID, &strRecvMsg); + } + } + else + { + M2M_DBG("Discard recv callback %d %d \r\n",u16SessionID , gastrSockets[sock].u16SessionID); + if(u16ReadSize < u16BufferSize) + hif_receive(0, NULL, 0, 1); + } + } + } + else if((u8OpCode == SOCKET_CMD_SEND) || (u8OpCode == SOCKET_CMD_SENDTO) || (u8OpCode == SOCKET_CMD_SSL_SEND)) + { + SOCKET sock; + sint16 s16Rcvd; + tstrSendReply strReply; + uint8 u8CallbackMsgID = SOCKET_MSG_SEND; + + if(u8OpCode == SOCKET_CMD_SENDTO) + u8CallbackMsgID = SOCKET_MSG_SENDTO; + + if(hif_receive(u32Address, (uint8*)&strReply, sizeof(tstrSendReply), 0) == M2M_SUCCESS) + { + uint16 u16SessionID = 0; + + sock = strReply.sock; + u16SessionID = strReply.u16SessionID; + M2M_DBG("send callback session ID = %d\r\n",u16SessionID); + + s16Rcvd = NM_BSP_B_L_16(strReply.s16SentBytes); + + if(u16SessionID == gastrSockets[sock].u16SessionID) + { + if(gpfAppSocketCb) + gpfAppSocketCb(sock,u8CallbackMsgID, &s16Rcvd); + } + else + { + M2M_DBG("Discard send callback %d %d \r\n",u16SessionID , gastrSockets[sock].u16SessionID); + } + } + } + else if(u8OpCode == SOCKET_CMD_PING) + { + tstrPingReply strPingReply; + if(hif_receive(u32Address, (uint8*)&strPingReply, sizeof(tstrPingReply), 1) == M2M_SUCCESS) + { + gfpPingCb = (void (*)(uint32 , uint32 , uint8))strPingReply.u32CmdPrivate; + if(gfpPingCb != NULL) + { + gfpPingCb(strPingReply.u32IPAddr, strPingReply.u32RTT, strPingReply.u8ErrorCode); + } + } + } +} +/********************************************************************* +Function + socketInit + +Description + +Return + None. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +void socketInit(void) +{ + if(gbSocketInit==0) + { + m2m_memset((uint8*)gastrSockets, 0, MAX_SOCKET * sizeof(tstrSocket)); + hif_register_cb(M2M_REQ_GROUP_IP,m2m_ip_cb); + gbSocketInit=1; + gu16SessionID = 0; + } +} +/********************************************************************* +Function + socketDeinit + +Description + +Return + None. + +Author + Samer Sarhan + +Version + 1.0 + +Date + 27 Feb 2015 +*********************************************************************/ +void socketDeinit(void) +{ + m2m_memset((uint8*)gastrSockets, 0, MAX_SOCKET * sizeof(tstrSocket)); + hif_register_cb(M2M_REQ_GROUP_IP, NULL); + gpfAppSocketCb = NULL; + gpfAppResolveCb = NULL; + gbSocketInit = 0; +} +/********************************************************************* +Function + registerSocketCallback + +Description + +Return + None. + +Author + Ahmed Ezzat + +Versio + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +void registerSocketCallback(tpfAppSocketCb pfAppSocketCb, tpfAppResolveCb pfAppResolveCb) +{ + gpfAppSocketCb = pfAppSocketCb; + gpfAppResolveCb = pfAppResolveCb; +} + +/********************************************************************* +Function + socket + +Description + Creates a socket. + +Return + - Negative value for error. + - ZERO or positive value as a socket ID if successful. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +SOCKET socket(uint16 u16Domain, uint8 u8Type, uint8 u8Flags) +{ + SOCKET sock = -1; + uint8 u8Count,u8SocketCount = MAX_SOCKET; + volatile tstrSocket *pstrSock; + + /* The only supported family is the AF_INET for UDP and TCP transport layer protocols. */ + if(u16Domain == AF_INET) + { + if(u8Type == SOCK_STREAM) + { + u8SocketCount = TCP_SOCK_MAX; + u8Count = 0; + } + else if(u8Type == SOCK_DGRAM) + { + /*--- UDP SOCKET ---*/ + u8SocketCount = MAX_SOCKET; + u8Count = TCP_SOCK_MAX; + } + else + return sock; + + for(;u8Count < u8SocketCount; u8Count ++) + { + pstrSock = &gastrSockets[u8Count]; + if(pstrSock->bIsUsed == 0) + { + m2m_memset((uint8*)pstrSock, 0, sizeof(tstrSocket)); + + pstrSock->bIsUsed = 1; + + /* The session ID is used to distinguish different socket connections + by comparing the assigned session ID to the one reported by the firmware*/ + ++gu16SessionID; + if(gu16SessionID == 0) + ++gu16SessionID; + + pstrSock->u16SessionID = gu16SessionID; + M2M_DBG("1 Socket %d session ID = %d\r\n",u8Count, gu16SessionID ); + sock = (SOCKET)u8Count; + + if(u8Flags & SOCKET_FLAGS_SSL) + { + tstrSSLSocketCreateCmd strSSLCreate; + strSSLCreate.sslSock = sock; + pstrSock->u8SSLFlags = SSL_FLAGS_ACTIVE | SSL_FLAGS_NO_TX_COPY; + SOCKET_REQUEST(SOCKET_CMD_SSL_CREATE, (uint8*)&strSSLCreate, sizeof(tstrSSLSocketCreateCmd), 0, 0, 0); + } + break; + } + } + } + return sock; +} +/********************************************************************* +Function + bind + +Description + Request to bind a socket on a local address. + +Return + + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 5 June 2012 +*********************************************************************/ +sint8 bind(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + if((pstrAddr != NULL) && (sock >= 0) && (gastrSockets[sock].bIsUsed == 1) && (u8AddrLen != 0)) + { + tstrBindCmd strBind; + + /* Build the bind request. */ + strBind.sock = sock; + m2m_memcpy((uint8 *)&strBind.strAddr, (uint8 *)pstrAddr, sizeof(tstrSockAddr)); + + strBind.strAddr.u16Family = strBind.strAddr.u16Family; + strBind.strAddr.u16Port = strBind.strAddr.u16Port; + strBind.strAddr.u32IPAddr = strBind.strAddr.u32IPAddr; + strBind.u16SessionID = gastrSockets[sock].u16SessionID; + + /* Send the request. */ + s8Ret = SOCKET_REQUEST(SOCKET_CMD_BIND, (uint8*)&strBind,sizeof(tstrBindCmd) , NULL , 0, 0); + if(s8Ret != SOCK_ERR_NO_ERROR) + { + s8Ret = SOCK_ERR_INVALID; + } + } + return s8Ret; +} +/********************************************************************* +Function + listen + +Description + + +Return + + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 5 June 2012 +*********************************************************************/ +sint8 listen(SOCKET sock, uint8 backlog) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + + if(sock >= 0 && (gastrSockets[sock].bIsUsed == 1)) + { + tstrListenCmd strListen; + + strListen.sock = sock; + strListen.u8BackLog = backlog; + strListen.u16SessionID = gastrSockets[sock].u16SessionID; + + s8Ret = SOCKET_REQUEST(SOCKET_CMD_LISTEN, (uint8*)&strListen, sizeof(tstrListenCmd), NULL, 0, 0); + if(s8Ret != SOCK_ERR_NO_ERROR) + { + s8Ret = SOCK_ERR_INVALID; + } + } + return s8Ret; +} +/********************************************************************* +Function + accept + +Description + +Return + + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 5 June 2012 +*********************************************************************/ +sint8 accept(SOCKET sock, struct sockaddr *addr, uint8 *addrlen) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + + if(sock >= 0 && (gastrSockets[sock].bIsUsed == 1) ) + { + s8Ret = SOCK_ERR_NO_ERROR; + } + return s8Ret; +} +/********************************************************************* +Function + connect + +Description + Connect to a remote TCP Server. + +Return + + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 5 June 2012 +*********************************************************************/ +sint8 connect(SOCKET sock, struct sockaddr *pstrAddr, uint8 u8AddrLen) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + if((sock >= 0) && (pstrAddr != NULL) && (gastrSockets[sock].bIsUsed == 1) && (u8AddrLen != 0)) + { + tstrConnectCmd strConnect; + uint8 u8Cmd = SOCKET_CMD_CONNECT; + if((gastrSockets[sock].u8SSLFlags) & SSL_FLAGS_ACTIVE) + { + u8Cmd = SOCKET_CMD_SSL_CONNECT; + strConnect.u8SslFlags = gastrSockets[sock].u8SSLFlags; + } + strConnect.sock = sock; + m2m_memcpy((uint8 *)&strConnect.strAddr, (uint8 *)pstrAddr, sizeof(tstrSockAddr)); + + strConnect.u16SessionID = gastrSockets[sock].u16SessionID; + s8Ret = SOCKET_REQUEST(u8Cmd, (uint8*)&strConnect,sizeof(tstrConnectCmd), NULL, 0, 0); + if(s8Ret != SOCK_ERR_NO_ERROR) + { + s8Ret = SOCK_ERR_INVALID; + } + } + return s8Ret; +} +/********************************************************************* +Function + send + +Description + +Return + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 5 June 2012 +*********************************************************************/ +sint16 send(SOCKET sock, void *pvSendBuffer, uint16 u16SendLength, uint16 flags) +{ + sint16 s16Ret = SOCK_ERR_INVALID_ARG; + + if((sock >= 0) && (pvSendBuffer != NULL) && (u16SendLength <= SOCKET_BUFFER_MAX_LENGTH) && (gastrSockets[sock].bIsUsed == 1)) + { + uint16 u16DataOffset; + tstrSendCmd strSend; + uint8 u8Cmd; + + u8Cmd = SOCKET_CMD_SEND; + u16DataOffset = TCP_TX_PACKET_OFFSET; + + strSend.sock = sock; + strSend.u16DataSize = NM_BSP_B_L_16(u16SendLength); + strSend.u16SessionID = gastrSockets[sock].u16SessionID; + + if(sock >= TCP_SOCK_MAX) + { + u16DataOffset = UDP_TX_PACKET_OFFSET; + } + if(gastrSockets[sock].u8SSLFlags & SSL_FLAGS_ACTIVE) + { + u8Cmd = SOCKET_CMD_SSL_SEND; + u16DataOffset = gastrSockets[sock].u16DataOffset; + } + + s16Ret = SOCKET_REQUEST(u8Cmd|M2M_REQ_DATA_PKT, (uint8*)&strSend, sizeof(tstrSendCmd), pvSendBuffer, u16SendLength, u16DataOffset); + if(s16Ret != SOCK_ERR_NO_ERROR) + { + s16Ret = SOCK_ERR_BUFFER_FULL; + } + } + return s16Ret; +} +/********************************************************************* +Function + sendto + +Description + +Return + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +sint16 sendto(SOCKET sock, void *pvSendBuffer, uint16 u16SendLength, uint16 flags, struct sockaddr *pstrDestAddr, uint8 u8AddrLen) +{ + sint16 s16Ret = SOCK_ERR_INVALID_ARG; + + if((sock >= 0) && (pvSendBuffer != NULL) && (u16SendLength <= SOCKET_BUFFER_MAX_LENGTH) && (gastrSockets[sock].bIsUsed == 1)) + { + if(gastrSockets[sock].bIsUsed) + { + tstrSendCmd strSendTo; + + m2m_memset((uint8*)&strSendTo, 0, sizeof(tstrSendCmd)); + + strSendTo.sock = sock; + strSendTo.u16DataSize = NM_BSP_B_L_16(u16SendLength); + strSendTo.u16SessionID = gastrSockets[sock].u16SessionID; + + if(pstrDestAddr != NULL) + { + struct sockaddr_in *pstrAddr; + pstrAddr = (void*)pstrDestAddr; + + strSendTo.strAddr.u16Family = pstrAddr->sin_family; + strSendTo.strAddr.u16Port = pstrAddr->sin_port; + strSendTo.strAddr.u32IPAddr = pstrAddr->sin_addr.s_addr; + } + s16Ret = SOCKET_REQUEST(SOCKET_CMD_SENDTO|M2M_REQ_DATA_PKT, (uint8*)&strSendTo, sizeof(tstrSendCmd), + pvSendBuffer, u16SendLength, UDP_TX_PACKET_OFFSET); + + if(s16Ret != SOCK_ERR_NO_ERROR) + { + s16Ret = SOCK_ERR_BUFFER_FULL; + } + } + } + return s16Ret; +} +/********************************************************************* +Function + recv + +Description + +Return + + +Author + Ahmed Ezzat + +Version + 1.0 + 2.0 9 April 2013 --> Add timeout for recv operation. + +Date + 5 June 2012 +*********************************************************************/ +sint16 recv(SOCKET sock, void *pvRecvBuf, uint16 u16BufLen, uint32 u32Timeoutmsec) +{ + sint16 s16Ret = SOCK_ERR_INVALID_ARG; + + if((sock >= 0) && (pvRecvBuf != NULL) && (u16BufLen != 0) && (gastrSockets[sock].bIsUsed == 1)) + { + s16Ret = SOCK_ERR_NO_ERROR; + gastrSockets[sock].pu8UserBuffer = (uint8*)pvRecvBuf; + gastrSockets[sock].u16UserBufferSize = u16BufLen; + + if(!gastrSockets[sock].bIsRecvPending) + { + tstrRecvCmd strRecv; + uint8 u8Cmd = SOCKET_CMD_RECV; + + gastrSockets[sock].bIsRecvPending = 1; + if(gastrSockets[sock].u8SSLFlags & SSL_FLAGS_ACTIVE) + { + u8Cmd = SOCKET_CMD_SSL_RECV; + } + + /* Check the timeout value. */ + if(u32Timeoutmsec == 0) + strRecv.u32Timeoutmsec = 0xFFFFFFFF; + else + strRecv.u32Timeoutmsec = NM_BSP_B_L_32(u32Timeoutmsec); + strRecv.sock = sock; + strRecv.u16SessionID = gastrSockets[sock].u16SessionID; + + s16Ret = SOCKET_REQUEST(u8Cmd, (uint8*)&strRecv, sizeof(tstrRecvCmd), NULL , 0, 0); + if(s16Ret != SOCK_ERR_NO_ERROR) + { + s16Ret = SOCK_ERR_BUFFER_FULL; + } + } + } + return s16Ret; +} +/********************************************************************* +Function + close + +Description + +Return + None. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +sint8 close(SOCKET sock) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + if(sock >= 0 && (gastrSockets[sock].bIsUsed == 1)) + { + uint8 u8Cmd = SOCKET_CMD_CLOSE; + tstrCloseCmd strclose; + strclose.sock = sock; + strclose.u16SessionID = gastrSockets[sock].u16SessionID; + + gastrSockets[sock].bIsUsed = 0; + gastrSockets[sock].u16SessionID =0; + + if(gastrSockets[sock].u8SSLFlags & SSL_FLAGS_ACTIVE) + { + u8Cmd = SOCKET_CMD_SSL_CLOSE; + } + s8Ret = SOCKET_REQUEST(u8Cmd, (uint8*)&strclose, sizeof(tstrCloseCmd), NULL,0, 0); + if(s8Ret != SOCK_ERR_NO_ERROR) + { + s8Ret = SOCK_ERR_INVALID; + } + m2m_memset((uint8*)&gastrSockets[sock], 0, sizeof(tstrSocket)); + } + return s8Ret; +} +/********************************************************************* +Function + recvfrom + +Description + +Return + + +Author + Ahmed Ezzat + +Version + 1.0 + 2.0 9 April 2013 --> Add timeout for recv operation. + +Date + 5 June 2012 +*********************************************************************/ +sint16 recvfrom(SOCKET sock, void *pvRecvBuf, uint16 u16BufLen, uint32 u32Timeoutmsec) +{ + sint16 s16Ret = SOCK_ERR_NO_ERROR; + if((sock >= 0) && (pvRecvBuf != NULL) && (u16BufLen != 0) && (gastrSockets[sock].bIsUsed == 1)) + { + if(gastrSockets[sock].bIsUsed) + { + s16Ret = SOCK_ERR_NO_ERROR; + gastrSockets[sock].pu8UserBuffer = (uint8*)pvRecvBuf; + gastrSockets[sock].u16UserBufferSize = u16BufLen; + + if(!gastrSockets[sock].bIsRecvPending) + { + tstrRecvCmd strRecv; + + gastrSockets[sock].bIsRecvPending = 1; + + /* Check the timeout value. */ + if(u32Timeoutmsec == 0) + strRecv.u32Timeoutmsec = 0xFFFFFFFF; + else + strRecv.u32Timeoutmsec = NM_BSP_B_L_32(u32Timeoutmsec); + strRecv.sock = sock; + strRecv.u16SessionID = gastrSockets[sock].u16SessionID; + + s16Ret = SOCKET_REQUEST(SOCKET_CMD_RECVFROM, (uint8*)&strRecv, sizeof(tstrRecvCmd), NULL , 0, 0); + if(s16Ret != SOCK_ERR_NO_ERROR) + { + s16Ret = SOCK_ERR_BUFFER_FULL; + } + } + } + } + else + { + s16Ret = SOCK_ERR_INVALID_ARG; + } + return s16Ret; +} +/********************************************************************* +Function + nmi_inet_addr + +Description + +Return + Unsigned 32-bit integer representing the IP address in Network + byte order. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +uint32 nmi_inet_addr(char *pcIpAddr) +{ + uint8 tmp; + uint32 u32IP = 0; + uint8 au8IP[4]; + uint8 c; + uint8 i, j; + + tmp = 0; + + for(i = 0; i < 4; ++i) + { + j = 0; + do + { + c = *pcIpAddr; + ++j; + if(j > 4) + { + return 0; + } + if(c == '.' || c == 0) + { + au8IP[i] = tmp; + tmp = 0; + } + else if(c >= '0' && c <= '9') + { + tmp = (tmp * 10) + (c - '0'); + } + else + { + return 0; + } + ++pcIpAddr; + } while(c != '.' && c != 0); + } + m2m_memcpy((uint8*)&u32IP, au8IP, 4); + return u32IP; +} +/********************************************************************* +Function + gethostbyname + +Description + +Return + None. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2012 +*********************************************************************/ +sint8 gethostbyname(uint8 * pcHostName) +{ + sint8 s8Err = SOCK_ERR_INVALID_ARG; + uint8 u8HostNameSize = (uint8)m2m_strlen(pcHostName); + if(u8HostNameSize <= HOSTNAME_MAX_SIZE) + { + s8Err = SOCKET_REQUEST(SOCKET_CMD_DNS_RESOLVE|M2M_REQ_DATA_PKT, (uint8*)pcHostName, u8HostNameSize + 1, NULL,0, 0); + if(s8Err != SOCK_ERR_NO_ERROR) + { + s8Err = SOCK_ERR_INVALID; + } + } + return s8Err; +} +/********************************************************************* +Function + setsockopt + +Description + +Return + None. + +Author + Abdelrahman Diab + +Version + 1.0 + +Date + 9 September 2014 +*********************************************************************/ +static sint8 sslSetSockOpt(SOCKET sock, uint8 u8Opt, const void *pvOptVal, uint16 u16OptLen) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + if(sock < TCP_SOCK_MAX) + { + if(gastrSockets[sock].u8SSLFlags & SSL_FLAGS_ACTIVE) + { + if(u8Opt == SO_SSL_BYPASS_X509_VERIF) + { + int optVal = *((int*)pvOptVal); + if(optVal) + { + gastrSockets[sock].u8SSLFlags |= SSL_FLAGS_BYPASS_X509; + } + else + { + gastrSockets[sock].u8SSLFlags &= ~SSL_FLAGS_BYPASS_X509; + } + s8Ret = SOCK_ERR_NO_ERROR; + } + else if(u8Opt == SO_SSL_ENABLE_SESSION_CACHING) + { + int optVal = *((int*)pvOptVal); + if(optVal) + { + gastrSockets[sock].u8SSLFlags |= SSL_FLAGS_CACHE_SESSION; + } + else + { + gastrSockets[sock].u8SSLFlags &= ~SSL_FLAGS_CACHE_SESSION; + } + s8Ret = SOCK_ERR_NO_ERROR; + } + else if(u8Opt == SO_SSL_SNI) + { + if(u16OptLen < HOSTNAME_MAX_SIZE) + { + uint8 *pu8SNI = (uint8*)pvOptVal; + tstrSSLSetSockOptCmd strCmd; + + strCmd.sock = sock; + strCmd.u16SessionID = gastrSockets[sock].u16SessionID; + strCmd.u8Option = u8Opt; + strCmd.u32OptLen = u16OptLen; + m2m_memcpy(strCmd.au8OptVal, pu8SNI, HOSTNAME_MAX_SIZE); + + if(SOCKET_REQUEST(SOCKET_CMD_SSL_SET_SOCK_OPT, (uint8*)&strCmd, sizeof(tstrSSLSetSockOptCmd), + 0, 0, 0) == M2M_ERR_MEM_ALLOC) + { + s8Ret = SOCKET_REQUEST(SOCKET_CMD_SSL_SET_SOCK_OPT | M2M_REQ_DATA_PKT, + (uint8*)&strCmd, sizeof(tstrSSLSetSockOptCmd), 0, 0, 0); + } + s8Ret = SOCK_ERR_NO_ERROR; + } + else + { + M2M_ERR("SNI Exceeds Max Length\n"); + } + } + else + { + M2M_ERR("Unknown SSL Socket Option %d\n",u8Opt); + } + } + else + { + M2M_ERR("Not SSL Socket\n"); + } + } + return s8Ret; +} +/********************************************************************* +Function + setsockopt + +Description + +Return + None. + +Author + Abdelrahman Diab + +Version + 1.0 + +Date + 9 September 2014 +*********************************************************************/ +sint8 setsockopt(SOCKET sock, uint8 u8Level, uint8 option_name, + const void *option_value, uint16 u16OptionLen) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + if((sock >= 0) && (option_value != NULL) && (gastrSockets[sock].bIsUsed == 1)) + { + if(u8Level == SOL_SSL_SOCKET) + { + s8Ret = sslSetSockOpt(sock, option_name, option_value, u16OptionLen); + } + else + { + uint8 u8Cmd = SOCKET_CMD_SET_SOCKET_OPTION; + tstrSetSocketOptCmd strSetSockOpt; + strSetSockOpt.u8Option=option_name; + strSetSockOpt.sock = sock; + strSetSockOpt.u32OptionValue = *(uint32*)option_value; + strSetSockOpt.u16SessionID = gastrSockets[sock].u16SessionID; + + s8Ret = SOCKET_REQUEST(u8Cmd, (uint8*)&strSetSockOpt, sizeof(tstrSetSocketOptCmd), NULL,0, 0); + if(s8Ret != SOCK_ERR_NO_ERROR) + { + s8Ret = SOCK_ERR_INVALID; + } + } + } + return s8Ret; +} +/********************************************************************* +Function + getsockopt + +Description + +Return + None. + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 24 August 2014 +*********************************************************************/ +sint8 getsockopt(SOCKET sock, uint8 u8Level, uint8 u8OptName, const void *pvOptValue, uint8* pu8OptLen) +{ + /* TBD */ + return M2M_SUCCESS; +} +/********************************************************************* +Function + m2m_ping_req + +Description + Send Ping request. + +Return + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2015 +*********************************************************************/ +sint8 m2m_ping_req(uint32 u32DstIP, uint8 u8TTL, tpfPingCb fpPingCb) +{ + sint8 s8Ret = M2M_ERR_INVALID_ARG; + + if((u32DstIP != 0) && (fpPingCb != NULL)) + { + tstrPingCmd strPingCmd; + + strPingCmd.u16PingCount = 1; + strPingCmd.u32DestIPAddr = u32DstIP; + strPingCmd.u32CmdPrivate = (uint32)fpPingCb; + strPingCmd.u8TTL = u8TTL; + + s8Ret = SOCKET_REQUEST(SOCKET_CMD_PING, (uint8*)&strPingCmd, sizeof(tstrPingCmd), NULL, 0, 0); + } + return s8Ret; +} +/********************************************************************* +Function + sslSetActiveCipherSuites + +Description + Send Ping request. + +Return + +Author + Ahmed Ezzat + +Version + 1.0 + +Date + 4 June 2015 +*********************************************************************/ +sint8 sslSetActiveCipherSuites(uint32 u32SslCsBMP) +{ + sint8 s8Ret = SOCK_ERR_INVALID_ARG; + if(u32SslCsBMP != 0) + { + tstrSslSetActiveCsList strCsList; + + strCsList.u32CsBMP = u32SslCsBMP; + s8Ret = SOCKET_REQUEST(SOCKET_CMD_SSL_SET_CS_LIST, (uint8*)&strCsList, sizeof(tstrSslSetActiveCsList), NULL, 0, 0); + } + return s8Ret; +} diff --git a/ext/drivers/atmel/winc1500/socket/source/socket_internal.h b/ext/drivers/atmel/winc1500/socket/source/socket_internal.h new file mode 100644 index 0000000000000..a747ff79d78f0 --- /dev/null +++ b/ext/drivers/atmel/winc1500/socket/source/socket_internal.h @@ -0,0 +1,68 @@ +/** + * + * \file + * + * \brief BSD alike socket interface internal types. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ +#ifndef __SOCKET_INTERNAL_H__ +#define __SOCKET_INTERNAL_H__ + + +#ifdef __cplusplus +extern "C" { +#endif + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +INCLUDES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +#include "socket/include/socket.h" +#include "socket/include/m2m_socket_host_if.h" + + +/*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=* +FUNCTION PROTOTYPES +*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*=*/ + +NMI_API void Socket_ReadSocketData(SOCKET sock, tstrSocketRecvMsg *pstrRecv,uint8 u8SocketMsg, + uint32 u32StartAddress,uint16 u16ReadCount); + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* __SOCKET_H__ */ diff --git a/ext/drivers/atmel/winc1500/spi_flash/include/spi_flash.h b/ext/drivers/atmel/winc1500/spi_flash/include/spi_flash.h new file mode 100644 index 0000000000000..bc52472929aad --- /dev/null +++ b/ext/drivers/atmel/winc1500/spi_flash/include/spi_flash.h @@ -0,0 +1,223 @@ +/** + * + * \file + * + * \brief WINC1500 SPI Flash. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +/** \defgroup SPIFLASH Spi Flash + * @file spi_flash.h + * @brief This file describe SPI flash APIs, how to use it and limitations with each one. + * @section Example + * This example illustrates a complete guide of how to use these APIs. + * @code{.c} + #include "spi_flash.h" + + #define DATA_TO_REPLACE "THIS IS A NEW SECTOR IN FLASH" + + int main() + { + uint8 au8FlashContent[FLASH_SECTOR_SZ] = {0}; + uint32 u32FlashTotalSize = 0; + uint32 u32FlashOffset = 0; + + ret = m2m_wifi_download_mode(); + if(M2M_SUCCESS != ret) + { + printf("Unable to enter download mode\r\n"); + } + else + { + u32FlashTotalSize = spi_flash_get_size(); + } + + while((u32FlashTotalSize > u32FlashOffset) && (M2M_SUCCESS == ret)) + { + ret = spi_flash_read(au8FlashContent, u32FlashOffset, FLASH_SECTOR_SZ); + if(M2M_SUCCESS != ret) + { + printf("Unable to read SPI sector\r\n"); + break; + } + memcpy(au8FlashContent, DATA_TO_REPLACE, strlen(DATA_TO_REPLACE)); + + ret = spi_flash_erase(u32FlashOffset, FLASH_SECTOR_SZ); + if(M2M_SUCCESS != ret) + { + printf("Unable to erase SPI sector\r\n"); + break; + } + + ret = spi_flash_write(au8FlashContent, u32FlashOffset, FLASH_SECTOR_SZ); + if(M2M_SUCCESS != ret) + { + printf("Unable to write SPI sector\r\n"); + break; + } + u32FlashOffset += FLASH_SECTOR_SZ; + } + + if(M2M_SUCCESS == ret) + { + printf("Successful operations\r\n"); + } + else + { + printf("Failed operations\r\n"); + } + + while(1); + return M2M_SUCCESS; + } + * @endcode + */ + +#ifndef __SPI_FLASH_H__ +#define __SPI_FLASH_H__ +#include "common/include/nm_common.h" +#include "bus_wrapper/include/nm_bus_wrapper.h" +#include "driver/source/nmbus.h" +#include "driver/source/nmasic.h" +#include "spi_flash/include/spi_flash_map.h" + +/** + * @fn spi_flash_enable + * @brief Enable spi flash operations + * @version 1.0 + */ +sint8 spi_flash_enable(uint8 enable); +/** \defgroup SPIFLASHAPI Function + * @ingroup SPIFLASH + */ + + /** @defgroup SPiFlashGetFn spi_flash_get_size + * @ingroup SPIFLASHAPI + */ + /**@{*/ +/*! + * @fn uint32 spi_flash_get_size(void); + * @brief Returns with \ref uint32 value which is total flash size\n + * @note Returned value in Mb (Mega Bit). + * @return SPI flash size in case of success and a ZERO value in case of failure. + */ +uint32 spi_flash_get_size(void); + /**@}*/ + + /** @defgroup SPiFlashRead spi_flash_read + * @ingroup SPIFLASHAPI + */ + /**@{*/ +/*! + * @fn sint8 spi_flash_read(uint8 *, uint32, uint32); + * @brief Read a specified portion of data from SPI Flash.\n + * @param [out] pu8Buf + * Pointer to data buffer which will fill in with data in case of successful operation. + * @param [in] u32Addr + * Address (Offset) to read from at the SPI flash. + * @param [in] u32Sz + * Total size of data to be read in bytes + * @warning + * - Address (offset) plus size of data must not exceed flash size.\n + * - No firmware is required for reading from SPI flash.\n + * - In case of there is a running firmware, it is required to pause your firmware first + * before any trial to access SPI flash to avoid any racing between host and running firmware on bus using + * @ref m2m_wifi_download_mode + * @note + * - It is blocking function\n + * @sa m2m_wifi_download_mode, spi_flash_get_size + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + */ +sint8 spi_flash_read(uint8 *pu8Buf, uint32 u32Addr, uint32 u32Sz); + /**@}*/ + + /** @defgroup SPiFlashWrite spi_flash_write + * @ingroup SPIFLASHAPI + */ + /**@{*/ +/*! + * @fn sint8 spi_flash_write(uint8 *, uint32, uint32); + * @brief Write a specified portion of data to SPI Flash.\n + * @param [in] pu8Buf + * Pointer to data buffer which contains the required to be written. + * @param [in] u32Offset + * Address (Offset) to write at the SPI flash. + * @param [in] u32Sz + * Total number of size of data bytes + * @note + * - It is blocking function\n + * - It is user's responsibility to verify that data has been written successfully + * by reading data again and compare it with the original. + * @warning + * - Address (offset) plus size of data must not exceed flash size.\n + * - No firmware is required for writing to SPI flash.\n + * - In case of there is a running firmware, it is required to pause your firmware first + * before any trial to access SPI flash to avoid any racing between host and running firmware on bus using + * @ref m2m_wifi_download_mode. + * - Before writing to any section, it is required to erase it first. + * @sa m2m_wifi_download_mode, spi_flash_get_size, spi_flash_erase + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + + */ +sint8 spi_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz); + /**@}*/ + + /** @defgroup SPiFlashErase spi_flash_erase + * @ingroup SPIFLASHAPI + */ + /**@{*/ +/*! + * @fn sint8 spi_flash_erase(uint32, uint32); + * @brief Erase a specified portion of SPI Flash.\n + * @param [in] u32Offset + * Address (Offset) to erase from the SPI flash. + * @param [in] u32Sz + * Size of SPI flash required to be erased. + * @note It is blocking function \n +* @warning +* - Address (offset) plus size of data must not exceed flash size.\n +* - No firmware is required for writing to SPI flash.\n + * - In case of there is a running firmware, it is required to pause your firmware first + * before any trial to access SPI flash to avoid any racing between host and running firmware on bus using + * @ref m2m_wifi_download_mode + * - It is blocking function\n + * @sa m2m_wifi_download_mode, spi_flash_get_size + * @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise. + + */ +sint8 spi_flash_erase(uint32 u32Offset, uint32 u32Sz); + /**@}*/ +#endif //__SPI_FLASH_H__ diff --git a/ext/drivers/atmel/winc1500/spi_flash/include/spi_flash_map.h b/ext/drivers/atmel/winc1500/spi_flash/include/spi_flash_map.h new file mode 100644 index 0000000000000..7c8b9b2d45061 --- /dev/null +++ b/ext/drivers/atmel/winc1500/spi_flash/include/spi_flash_map.h @@ -0,0 +1,235 @@ +/** + * + * \file + * + * \brief WINC1500 SPI Flash. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +/** +* @file spi_flash_map.h +* @brief This module contains spi flash CONTENT +*/ +#ifndef __SPI_FLASH_MAP_H__ +#define __SPI_FLASH_MAP_H__ + +#define FLASH_MAP_VER_0 (0) +#define FLAAH_MAP_VER_1 (1) + +#define FLASH_MAP_VERSION FLAAH_MAP_VER_1 + +//#define DOWNLOAD_ROLLBACK +//#define OTA_GEN +#define _PROGRAM_POWER_SAVE_ + +/* =======*=======*=======*=======*======= + * General Sizes for Flash Memory + * =======*=======*=======*=======*======= + */ + +#define FLASH_START_ADDR (0UL) +/*! location :xxxK + * "S:xxxK" -means-> Size is :xxxK + */ + +/* + * Boot Firmware: which used to select which firmware to run + * + */ +#define M2M_BOOT_FIRMWARE_STARTING_ADDR (FLASH_START_ADDR) +#define M2M_BOOT_FIRMWARE_FLASH_SZ (FLASH_SECTOR_SZ) + +/* + * Control Section: which used by Boot firmware + * + */ +#define M2M_CONTROL_FLASH_OFFSET (M2M_BOOT_FIRMWARE_STARTING_ADDR + M2M_BOOT_FIRMWARE_FLASH_SZ) +#define M2M_CONTROL_FLASH_BKP_OFFSET (M2M_CONTROL_FLASH_OFFSET + FLASH_SECTOR_SZ) +#define M2M_CONTROL_FLASH_SEC_SZ (FLASH_SECTOR_SZ) +#define M2M_CONTROL_FLASH_TOTAL_SZ (FLASH_SECTOR_SZ * 2) + +/* + * LUT for PLL and TX Gain settings: + * + */ +#define M2M_PLL_FLASH_OFFSET (M2M_CONTROL_FLASH_OFFSET + M2M_CONTROL_FLASH_TOTAL_SZ) +#define M2M_PLL_FLASH_SZ (1024 * 1) +#define M2M_GAIN_FLASH_OFFSET (M2M_PLL_FLASH_OFFSET + M2M_PLL_FLASH_SZ) +#define M2M_GAIN_FLASH_SZ (M2M_CONFIG_SECT_TOTAL_SZ - M2M_PLL_FLASH_SZ) +#define M2M_CONFIG_SECT_TOTAL_SZ (FLASH_SECTOR_SZ) + +/* + * Certificate: + * + */ +#define M2M_TLS_FLASH_ROOTCERT_CACHE_OFFSET (M2M_PLL_FLASH_OFFSET + M2M_CONFIG_SECT_TOTAL_SZ) +#define M2M_TLS_FLASH_ROOTCERT_CACHE_SIZE (FLASH_SECTOR_SZ * 1) + +/* + * Scratch: + * + */ +#define M2M_TLS_FLASH_SESSION_CACHE_OFFSET (M2M_TLS_FLASH_ROOTCERT_CACHE_OFFSET + M2M_TLS_FLASH_ROOTCERT_CACHE_SIZE) +#define M2M_TLS_FLASH_SESSION_CACHE_SIZE (FLASH_SECTOR_SZ * 1) + +/* + * reserved section + * + */ +#define M2M_RESERVED_FLASH_OFFSET (M2M_TLS_FLASH_SESSION_CACHE_OFFSET + M2M_TLS_FLASH_SESSION_CACHE_SIZE) +#define M2M_RESERVED_FLASH_SZ (FLASH_SECTOR_SZ * 1) +/* + * HTTP Files + * + */ +#define M2M_HTTP_MEM_FLASH_OFFSET (M2M_RESERVED_FLASH_OFFSET + M2M_RESERVED_FLASH_SZ) +#define M2M_HTTP_MEM_FLASH_SZ (FLASH_SECTOR_SZ * 2) +/* + * Saved Connection Parameters: + * + */ +#define M2M_CACHED_CONNS_FLASH_OFFSET (M2M_HTTP_MEM_FLASH_OFFSET + M2M_HTTP_MEM_FLASH_SZ) +#define M2M_CACHED_CONNS_FLASH_SZ (FLASH_SECTOR_SZ * 1) + +/* + * + * Common section size + */ + +#define M2M_COMMON_DATA_SEC (M2M_BOOT_FIRMWARE_FLASH_SZ + M2M_CONTROL_FLASH_TOTAL_SZ + M2M_CONFIG_SECT_TOTAL_SZ + \ + M2M_TLS_FLASH_ROOTCERT_CACHE_SIZE + M2M_TLS_FLASH_SESSION_CACHE_SIZE + \ + M2M_HTTP_MEM_FLASH_SZ + M2M_CACHED_CONNS_FLASH_SZ + M2M_RESERVED_FLASH_SZ) +/* + * + * OTA image1 Offset + */ + +#define M2M_OTA_IMAGE1_OFFSET (M2M_CACHED_CONNS_FLASH_OFFSET + M2M_CACHED_CONNS_FLASH_SZ) +/* + * Firmware Offset + * + */ +#if (defined _FIRMWARE_)||(defined OTA_GEN) +#define M2M_FIRMWARE_FLASH_OFFSET (0UL) +#else +#if (defined DOWNLOAD_ROLLBACK) +#define M2M_FIRMWARE_FLASH_OFFSET (M2M_OTA_IMAGE2_OFFSET) +#else +#define M2M_FIRMWARE_FLASH_OFFSET (M2M_OTA_IMAGE1_OFFSET) +#endif +#endif +/* + * + * Firmware + */ +#define M2M_FIRMWARE_FLASH_SZ (236*1024UL) +/** + * + * OTA image Size + */ +#define OTA_IMAGE_SIZE (M2M_FIRMWARE_FLASH_SZ) +/** + * + * Flash Total size + */ +#define FLASH_IMAGE1_CONTENT_SZ (M2M_COMMON_DATA_SEC + OTA_IMAGE_SIZE) + +/** + * + * OTA image 2 offset + */ +#define M2M_OTA_IMAGE2_OFFSET (FLASH_IMAGE1_CONTENT_SZ) + +/* + * App(Cortus App 4M): App. which runs over firmware + * + */ +#define M2M_APP_4M_MEM_FLASH_SZ (FLASH_SECTOR_SZ * 10) +#define M2M_APP_4M_MEM_FLASH_OFFSET (FLASH_4M_TOTAL_SZ - M2M_APP_4M_MEM_FLASH_SZ) + +/* Check if total size of content + * don't exceed total size of memory allowed + **/ +#if (M2M_COMMON_DATA_SEC + (OTA_IMAGE_SIZE *2)> FLASH_4M_TOTAL_SZ) +#error "Excced 4M Flash Size" +#endif /* (FLASH_CONTENT_SZ > FLASH_TOTAL_SZ) */ + + +#endif /* __SPI_FLASH_MAP_H__ */ diff --git a/ext/drivers/atmel/winc1500/spi_flash/source/spi_flash.c b/ext/drivers/atmel/winc1500/spi_flash/source/spi_flash.c new file mode 100644 index 0000000000000..9e82cdd08b137 --- /dev/null +++ b/ext/drivers/atmel/winc1500/spi_flash/source/spi_flash.c @@ -0,0 +1,698 @@ +/** + * + * \file + * + * \brief WINC1500 SPI Flash. + * + * Copyright (c) 2016 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifdef PROFILING +#include "windows.h" +#endif +#include "spi_flash/include/spi_flash.h" +#define DUMMY_REGISTER (0x1084) + +#define TIMEOUT (-1) /*MS*/ + +//#define DISABLE_UNSED_FLASH_FUNCTIONS + +#define HOST_SHARE_MEM_BASE (0xd0000UL) +#define CORTUS_SHARE_MEM_BASE (0x60000000UL) +#define NMI_SPI_FLASH_ADDR (0x111c) +/*********************************************************** +SPI Flash DMA +***********************************************************/ +#define GET_UINT32(X,Y) (X[0+Y] + ((uint32)X[1+Y]<<8) + ((uint32)X[2+Y]<<16) +((uint32)X[3+Y]<<24)) +#define SPI_FLASH_BASE (0x10200) +#define SPI_FLASH_MODE (SPI_FLASH_BASE + 0x00) +#define SPI_FLASH_CMD_CNT (SPI_FLASH_BASE + 0x04) +#define SPI_FLASH_DATA_CNT (SPI_FLASH_BASE + 0x08) +#define SPI_FLASH_BUF1 (SPI_FLASH_BASE + 0x0c) +#define SPI_FLASH_BUF2 (SPI_FLASH_BASE + 0x10) +#define SPI_FLASH_BUF_DIR (SPI_FLASH_BASE + 0x14) +#define SPI_FLASH_TR_DONE (SPI_FLASH_BASE + 0x18) +#define SPI_FLASH_DMA_ADDR (SPI_FLASH_BASE + 0x1c) +#define SPI_FLASH_MSB_CTL (SPI_FLASH_BASE + 0x20) +#define SPI_FLASH_TX_CTL (SPI_FLASH_BASE + 0x24) + +/*********************************************/ +/* STATIC FUNCTIONS */ +/*********************************************/ + +/** +* @fn spi_flash_read_status_reg +* @brief Read status register +* @param[OUT] val + value of status reg +* @return Status of execution +*/ +static sint8 spi_flash_read_status_reg(uint8 * val) +{ + sint8 ret = M2M_SUCCESS; + uint8 cmd[1]; + uint32 reg; + + cmd[0] = 0x05; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 4); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x01); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, DUMMY_REGISTER); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)®); + if(M2M_SUCCESS != ret) break; + } + while(reg != 1); + + reg = (M2M_SUCCESS == ret)?(nm_read_reg(DUMMY_REGISTER)):(0); + *val = (uint8)(reg & 0xff); + return ret; +} + +#ifdef DISABLE_UNSED_FLASH_FUNCTIONS +/** +* @fn spi_flash_read_security_reg +* @brief Read security register +* @return Security register value +*/ +static uint8 spi_flash_read_security_reg(void) +{ + uint8 cmd[1]; + uint32 reg; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x2b; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 1); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x01); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, DUMMY_REGISTER); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)®); + if(M2M_SUCCESS != ret) break; + } + while(reg != 1); + reg = (M2M_SUCCESS == ret)?(nm_read_reg(DUMMY_REGISTER)):(0); + + return (sint8)reg & 0xff; +} + +/** +* @fn spi_flash_gang_unblock +* @brief Unblock all flash area +*/ +static sint8 spi_flash_gang_unblock(void) +{ + uint8 cmd[1]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x98; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 0); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x01); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} + +/** +* @fn spi_flash_clear_security_flags +* @brief Clear all security flags +*/ +static sint8 spi_flash_clear_security_flags(void) +{ + uint8 cmd[1]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x30; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 0); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x01); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} +#endif + +/** +* @fn spi_flash_load_to_cortus_mem +* @brief Load data from SPI flash into cortus memory +* @param[IN] u32MemAdr +* Cortus load address. It must be set to its AHB access address +* @param[IN] u32FlashAdr +* Address to read from at the SPI flash +* @param[IN] u32Sz +* Data size +* @return Status of execution +*/ +static sint8 spi_flash_load_to_cortus_mem(uint32 u32MemAdr, uint32 u32FlashAdr, uint32 u32Sz) +{ + uint8 cmd[5]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x0b; + cmd[1] = (uint8)(u32FlashAdr >> 16); + cmd[2] = (uint8)(u32FlashAdr >> 8); + cmd[3] = (uint8)(u32FlashAdr); + cmd[4] = 0xA5; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, u32Sz); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]|(cmd[1]<<8)|(cmd[2]<<16)|(cmd[3]<<24)); + ret += nm_write_reg(SPI_FLASH_BUF2, cmd[4]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x1f); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, u32MemAdr); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 5 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} + +/** +* @fn spi_flash_sector_erase +* @brief Erase sector (4KB) +* @param[IN] u32FlashAdr +* Any memory address within the sector +* @return Status of execution +*/ +static sint8 spi_flash_sector_erase(uint32 u32FlashAdr) +{ + uint8 cmd[4]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x20; + cmd[1] = (uint8)(u32FlashAdr >> 16); + cmd[2] = (uint8)(u32FlashAdr >> 8); + cmd[3] = (uint8)(u32FlashAdr); + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 0); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]|(cmd[1]<<8)|(cmd[2]<<16)|(cmd[3]<<24)); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x0f); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 4 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} + +/** +* @fn spi_flash_write_enable +* @brief Send write enable command to SPI flash +* @return Status of execution +*/ +static sint8 spi_flash_write_enable(void) +{ + uint8 cmd[1]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x06; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 0); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x01); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} + +/** +* @fn spi_flash_write_disable +* @brief Send write disable command to SPI flash +*/ +static sint8 spi_flash_write_disable(void) +{ + uint8 cmd[1]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + cmd[0] = 0x04; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 0); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x01); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} + +/** +* @fn spi_flash_page_program +* @brief Write data (less than page size) from cortus memory to SPI flash +* @param[IN] u32MemAdr +* Cortus data address. It must be set to its AHB access address +* @param[IN] u32FlashAdr +* Address to write to at the SPI flash +* @param[IN] u32Sz +* Data size +*/ +static sint8 spi_flash_page_program(uint32 u32MemAdr, uint32 u32FlashAdr, uint32 u32Sz) +{ + uint8 cmd[4]; + uint32 val = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x02; + cmd[1] = (uint8)(u32FlashAdr >> 16); + cmd[2] = (uint8)(u32FlashAdr >> 8); + cmd[3] = (uint8)(u32FlashAdr); + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 0); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]|(cmd[1]<<8)|(cmd[2]<<16)|(cmd[3]<<24)); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x0f); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, u32MemAdr); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 4 | (1<<7) | ((u32Sz & 0xfffff) << 8)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)&val); + if(M2M_SUCCESS != ret) break; + } + while(val != 1); + + return ret; +} + +/** +* @fn spi_flash_read_internal +* @brief Read from data from SPI flash +* @param[OUT] pu8Buf +* Pointer to data buffer +* @param[IN] u32Addr +* Address to read from at the SPI flash +* @param[IN] u32Sz +* Data size +*/ +static sint8 spi_flash_read_internal(uint8 *pu8Buf, uint32 u32Addr, uint32 u32Sz) +{ + sint8 ret = M2M_SUCCESS; + /* read size must be < 64KB */ + ret = spi_flash_load_to_cortus_mem(HOST_SHARE_MEM_BASE, u32Addr, u32Sz); + if(M2M_SUCCESS != ret) goto ERR; + ret = nm_read_block(HOST_SHARE_MEM_BASE, pu8Buf, u32Sz); +ERR: + return ret; +} + +/** +* @fn spi_flash_pp +* @brief Program data of size less than a page (256 bytes) at the SPI flash +* @param[IN] u32Offset +* Address to write to at the SPI flash +* @param[IN] pu8Buf +* Pointer to data buffer +* @param[IN] u32Sz +* Data size +* @return Status of execution +*/ +static sint8 spi_flash_pp(uint32 u32Offset, uint8 *pu8Buf, uint16 u16Sz) +{ + sint8 ret = M2M_SUCCESS; + uint8 tmp; + spi_flash_write_enable(); + /* use shared packet memory as temp mem */ + ret += nm_write_block(HOST_SHARE_MEM_BASE, pu8Buf, u16Sz); + ret += spi_flash_page_program(HOST_SHARE_MEM_BASE, u32Offset, u16Sz); + ret += spi_flash_read_status_reg(&tmp); + do + { + if(ret != M2M_SUCCESS) goto ERR; + ret += spi_flash_read_status_reg(&tmp); + }while(tmp & 0x01); + ret += spi_flash_write_disable(); +ERR: + return ret; +} + +/** +* @fn spi_flash_rdid +* @brief Read SPI Flash ID +* @return SPI FLash ID +*/ +static uint32 spi_flash_rdid(void) +{ + unsigned char cmd[1]; + uint32 reg = 0; + uint32 cnt = 0; + sint8 ret = M2M_SUCCESS; + + cmd[0] = 0x9f; + + ret += nm_write_reg(SPI_FLASH_DATA_CNT, 4); + ret += nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + ret += nm_write_reg(SPI_FLASH_BUF_DIR, 0x1); + ret += nm_write_reg(SPI_FLASH_DMA_ADDR, DUMMY_REGISTER); + ret += nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1<<7)); + do + { + ret += nm_read_reg_with_ret(SPI_FLASH_TR_DONE, (uint32 *)®); + if(M2M_SUCCESS != ret) break; + if(++cnt > 500) + { + ret = M2M_ERR_INIT; + break; + } + } + while(reg != 1); + reg = (M2M_SUCCESS == ret)?(nm_read_reg(DUMMY_REGISTER)):(0); + M2M_PRINT("Flash ID %x \n",(unsigned int)reg); + return reg; +} + +/** +* @fn spi_flash_unlock +* @brief Unlock SPI Flash +*/ +#if 0 +static void spi_flash_unlock(void) +{ + uint8 tmp; + tmp = spi_flash_read_security_reg(); + spi_flash_clear_security_flags(); + if(tmp & 0x80) + { + spi_flash_write_enable(); + spi_flash_gang_unblock(); + } +} +#endif +static void spi_flash_enter_low_power_mode(void) { + volatile unsigned long tmp; + unsigned char* cmd = (unsigned char*) &tmp; + + cmd[0] = 0xb9; + + nm_write_reg(SPI_FLASH_DATA_CNT, 0); + nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + nm_write_reg(SPI_FLASH_BUF_DIR, 0x1); + nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1 << 7)); + while(nm_read_reg(SPI_FLASH_TR_DONE) != 1); +} + + +static void spi_flash_leave_low_power_mode(void) { + volatile unsigned long tmp; + unsigned char* cmd = (unsigned char*) &tmp; + + cmd[0] = 0xab; + + nm_write_reg(SPI_FLASH_DATA_CNT, 0); + nm_write_reg(SPI_FLASH_BUF1, cmd[0]); + nm_write_reg(SPI_FLASH_BUF_DIR, 0x1); + nm_write_reg(SPI_FLASH_DMA_ADDR, 0); + nm_write_reg(SPI_FLASH_CMD_CNT, 1 | (1 << 7)); + while(nm_read_reg(SPI_FLASH_TR_DONE) != 1); +} +/*********************************************/ +/* GLOBAL FUNCTIONS */ +/*********************************************/ +/** + * @fn spi_flash_enable + * @brief Enable spi flash operations + */ +sint8 spi_flash_enable(uint8 enable) +{ + sint8 s8Ret = M2M_SUCCESS; + if(REV(nmi_get_chipid()) >= REV_3A0) { + uint32 u32Val; + + /* Enable pinmux to SPI flash. */ + s8Ret = nm_read_reg_with_ret(0x1410, &u32Val); + if(s8Ret != M2M_SUCCESS) { + goto ERR1; + } + /* GPIO15/16/17/18 */ + u32Val &= ~((0x7777ul) << 12); + u32Val |= ((0x1111ul) << 12); + nm_write_reg(0x1410, u32Val); + if(enable) { + spi_flash_leave_low_power_mode(); + } else { + spi_flash_enter_low_power_mode(); + } + /* Disable pinmux to SPI flash to minimize leakage. */ + u32Val &= ~((0x7777ul) << 12); + u32Val |= ((0x0010ul) << 12); + nm_write_reg(0x1410, u32Val); + } +ERR1: + return s8Ret; +} +/** +* @fn spi_flash_read +* @brief Read from data from SPI flash +* @param[OUT] pu8Buf +* Pointer to data buffer +* @param[IN] u32offset +* Address to read from at the SPI flash +* @param[IN] u32Sz +* Data size +* @return Status of execution +* @note Data size is limited by the SPI flash size only +*/ +sint8 spi_flash_read(uint8 *pu8Buf, uint32 u32offset, uint32 u32Sz) +{ + sint8 ret = M2M_SUCCESS; + if(u32Sz > FLASH_BLOCK_SIZE) + { + do + { + ret = spi_flash_read_internal(pu8Buf, u32offset, FLASH_BLOCK_SIZE); + if(M2M_SUCCESS != ret) goto ERR; + u32Sz -= FLASH_BLOCK_SIZE; + u32offset += FLASH_BLOCK_SIZE; + pu8Buf += FLASH_BLOCK_SIZE; + } while(u32Sz > FLASH_BLOCK_SIZE); + } + + ret = spi_flash_read_internal(pu8Buf, u32offset, u32Sz); + +ERR: + return ret; +} + +/** +* @fn spi_flash_write +* @brief Proram SPI flash +* @param[IN] pu8Buf +* Pointer to data buffer +* @param[IN] u32Offset +* Address to write to at the SPI flash +* @param[IN] u32Sz +* Data size +* @return Status of execution +*/ +sint8 spi_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz) +{ +#ifdef PROFILING + uint32 t1 = 0; + uint32 percent =0; + uint32 tpercent =0; +#endif + sint8 ret = M2M_SUCCESS; + uint32 u32wsz; + uint32 u32off; + uint32 u32Blksz; + u32Blksz = FLASH_PAGE_SZ; + u32off = u32Offset % u32Blksz; +#ifdef PROFILING + tpercent = (u32Sz/u32Blksz)+((u32Sz%u32Blksz)>0); + t1 = GetTickCount(); + M2M_PRINT(">Start programming...\r\n"); +#endif + if(u32Sz<=0) + { + M2M_ERR("Data size = %d",(int)u32Sz); + ret = M2M_ERR_FAIL; + goto ERR; + } + + if (u32off)/*first part of data in the address page*/ + { + u32wsz = u32Blksz - u32off; + if(spi_flash_pp(u32Offset, pu8Buf, (uint16)BSP_MIN(u32Sz, u32wsz))!=M2M_SUCCESS) + { + ret = M2M_ERR_FAIL; + goto ERR; + } + if (u32Sz < u32wsz) goto EXIT; + pu8Buf += u32wsz; + u32Offset += u32wsz; + u32Sz -= u32wsz; + } + while (u32Sz > 0) + { + u32wsz = BSP_MIN(u32Sz, u32Blksz); + + /*write complete page or the remaining data*/ + if(spi_flash_pp(u32Offset, pu8Buf, (uint16)u32wsz)!=M2M_SUCCESS) + { + ret = M2M_ERR_FAIL; + goto ERR; + } + pu8Buf += u32wsz; + u32Offset += u32wsz; + u32Sz -= u32wsz; +#ifdef PROFILING + percent++; + printf("\r>Complete Percentage = %d%%.\r",((percent*100)/tpercent)); +#endif + } +EXIT: +#ifdef PROFILING + M2M_PRINT("\rDone\t\t\t\t\t\t"); + M2M_PRINT("\n#Programming time = %f sec\n\r",(GetTickCount() - t1)/1000.0); +#endif +ERR: + return ret; +} + +/** +* @fn spi_flash_erase +* @brief Erase from data from SPI flash +* @param[IN] u32Offset +* Address to write to at the SPI flash +* @param[IN] u32Sz +* Data size +* @return Status of execution +* @note Data size is limited by the SPI flash size only +*/ +sint8 spi_flash_erase(uint32 u32Offset, uint32 u32Sz) +{ + uint32 i = 0; + sint8 ret = M2M_SUCCESS; + uint8 tmp = 0; +#ifdef PROFILING + uint32 t; + t = GetTickCount(); +#endif + M2M_PRINT("\r\n>Start erasing...\r\n"); + for(i = u32Offset; i < (u32Sz +u32Offset); i += (16*FLASH_PAGE_SZ)) + { + ret += spi_flash_write_enable(); + ret += spi_flash_read_status_reg(&tmp); + ret += spi_flash_sector_erase(i + 10); + ret += spi_flash_read_status_reg(&tmp); + do + { + if(ret != M2M_SUCCESS) goto ERR; + ret += spi_flash_read_status_reg(&tmp); + }while(tmp & 0x01); + + } + M2M_PRINT("Done\r\n"); +#ifdef PROFILING + M2M_PRINT("#Erase time = %f sec\n", (GetTickCount()-t)/1000.0); +#endif +ERR: + return ret; +} + +/** +* @fn spi_flash_get_size +* @brief Get size of SPI Flash +* @return Size of Flash +*/ +uint32 spi_flash_get_size(void) +{ + uint32 u32FlashId = 0, u32FlashPwr = 0; + static uint32 gu32InernalFlashSize= 0; + + if(!gu32InernalFlashSize) + { + u32FlashId = spi_flash_rdid();//spi_flash_probe(); + if(u32FlashId != 0xffffffff) + { + /*flash size is the third byte from the FLASH RDID*/ + u32FlashPwr = ((u32FlashId>>16)&0xff) - 0x11; /*2MBIT is the min*/ + /*That number power 2 to get the flash size*/ + gu32InernalFlashSize = 1<offload) { + return 0; + } +#endif + return iface->l2->reserve(iface, (void *)dst_ip6); } @@ -1223,6 +1229,16 @@ struct net_if_api { (NET_IF_EVENT_GET_NAME(dev_name, sfx)) __used \ __attribute__((__section__(".net_if_event.data"))) = {} +#define NET_IF_OFFLOAD_INIT(dev_name, sfx, _mtu) \ + static struct net_if (NET_IF_GET_NAME(dev_name, sfx)) __used \ + __attribute__((__section__(".net_if.data"))) = { \ + .dev = &(__device_##dev_name), \ + .mtu = _mtu, \ + NET_IF_DHCPV4_INIT \ + }; \ + static struct k_poll_event \ + (NET_IF_EVENT_GET_NAME(dev_name, sfx)) __used \ + __attribute__((__section__(".net_if_event.data"))) = {} /* Network device initialization macros */ @@ -1234,6 +1250,13 @@ struct net_if_api { NET_L2_DATA_INIT(dev_name, 0, l2_ctx_type); \ NET_IF_INIT(dev_name, 0, l2, mtu) +#define NET_DEVICE_OFFLOAD_INIT(dev_name, drv_name, init_fn, \ + data, cfg_info, prio, api, mtu) \ + DEVICE_AND_API_INIT(dev_name, drv_name, init_fn, data, \ + cfg_info, POST_KERNEL, prio, api); \ + NET_IF_OFFLOAD_INIT(dev_name, 0, mtu) + + /** * If your network device needs more than one instance of a network interface, * Use this macro below and provide a different instance suffix each time diff --git a/include/net/net_l2.h b/include/net/net_l2.h index 253cf892f4e54..fea9c69e7a677 100644 --- a/include/net/net_l2.h +++ b/include/net/net_l2.h @@ -79,11 +79,6 @@ NET_L2_DECLARE_PUBLIC(IEEE802154_L2); #define BLUETOOTH_L2_CTX_TYPE void* #endif /* CONFIG_NET_L2_BLUETOOTH */ -#ifdef CONFIG_NET_OFFLOAD -#define OFFLOAD_IP_L2 OFFLOAD_IP -#define OFFLOAD_IP_L2_CTX_TYPE void* -#endif /* CONFIG_NET_OFFLOAD */ - extern struct net_l2 __net_l2_end[]; #define NET_L2_INIT(_name, _recv_fn, _send_fn, _reserve_fn, _enable_fn) \ diff --git a/include/net/wifi_mgmt.h b/include/net/wifi_mgmt.h new file mode 100644 index 0000000000000..c885a12da4882 --- /dev/null +++ b/include/net/wifi_mgmt.h @@ -0,0 +1,139 @@ +/* + * Copyright (c) 2017 IpTronix S.r.l. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/** + * @file + * @brief Public WiFi API + */ + +#ifndef __WIFI_MGMT_H__ +#define __WIFI_MGMT_H__ + +#include +#include + +#include + +/* Management part definitions */ + +#define _NET_WIFI_LAYER NET_MGMT_LAYER_L2 +#define _NET_WIFI_CODE 0x11 +#define _NET_WIFI_BASE (NET_MGMT_IFACE_BIT | \ + NET_MGMT_LAYER(_NET_WIFI_LAYER) |\ + NET_MGMT_LAYER_CODE(_NET_WIFI_CODE)) +#define _NET_WIFI_EVENT (_NET_WIFI_BASE | NET_MGMT_EVENT_BIT) + +enum net_request_wifi_cmd { + NET_REQUEST_WIFI_CMD_SCAN = 1, + NET_REQUEST_WIFI_CMD_CANCEL_SCAN, + NET_REQUEST_WIFI_CMD_AP_CONNECT, + NET_REQUEST_WIFI_CMD_AP_DISCONNECT, + NET_REQUEST_WIFI_CMD_SET_CHAN, + NET_REQUEST_WIFI_CMD_GET_CHAN, +}; + +#define NET_REQUEST_WIFI_CMD_SCAN \ + (_NET_WIFI_BASE | NET_REQUEST_WIFI_CMD_SCAN) +NET_MGMT_DEFINE_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_SCAN); + +#define NET_REQUEST_WIFI_CMD_CANCEL_SCAN \ + (_NET_WIFI_BASE | NET_REQUEST_WIFI_CMD_CANCEL_SCAN) +NET_MGMT_DEFINE_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_CANCEL_SCAN); + +#define NET_REQUEST_WIFI_CMD_AP_CONNECT \ + (_NET_WIFI_BASE | NET_REQUEST_WIFI_CMD_AP_CONNECT) +NET_MGMT_DEFINE_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_AP_CONNECT); + +#define NET_REQUEST_WIFI_CMD_AP_DISCONNECT \ + (_NET_WIFI_BASE | NET_REQUEST_WIFI_CMD_AP_DISCONNECT) +NET_MGMT_DEFINE_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_AP_DISCONNECT); + +enum net_event_wifi_cmd { + NET_EVENT_WIFI_CMD_SCAN_RESULT = 1, +}; + +#define NET_EVENT_WIFI_SCAN_RESULT \ + (_NET_WIFI_EVENT | NET_EVENT_WIFI_CMD_SCAN_RESULT) + +#define WEP (1<<0) +#define TKIP (1<<1) +#define AES (1<<2) +#define SHARED (1<<3) +#define WPA (1<<4) +#define WPA2 (1<<5) +#define ENTERPRISE (1<<6) +#define WPS (1<<7) +#define IBSS (1<<8) + +typedef enum { + WIFI_SECURITY_OPEN = 0, + WIFI_SECURITY_WEP_PSK = WEP, + WIFI_SECURITY_WEP_SHARED = (WEP | SHARED), + WIFI_SECURITY_WPA_TKIP_PSK = (WPA | TKIP), + WIFI_SECURITY_WPA_AES_PSK = (WPA | AES), + WIFI_SECURITY_WPA_MIXED_PSK = (WPA | AES | TKIP), + WIFI_SECURITY_WPA2_AES_PSK = (WPA2 | AES), + WIFI_SECURITY_WPA2_TKIP_PSK = (WPA2 | TKIP), + WIFI_SECURITY_WPA2_MIXED_PSK = (WPA2 | AES | TKIP), + + WIFI_SECURITY_WPA_TKIP_ENT = (ENTERPRISE | WPA | TKIP), + WIFI_SECURITY_WPA_AES_ENT = (ENTERPRISE | WPA | AES), + WIFI_SECURITY_WPA_MIXED_ENT = (ENTERPRISE | WPA | AES | TKIP), + WIFI_SECURITY_WPA2_TKIP_ENT = (ENTERPRISE | WPA2 | TKIP), + WIFI_SECURITY_WPA2_AES_ENT = (ENTERPRISE | WPA2 | AES), + WIFI_SECURITY_WPA2_MIXED_ENT = (ENTERPRISE | WPA2 | AES | TKIP), + + WIFI_SECURITY_IBSS_OPEN = (IBSS), + WIFI_SECURITY_WPS_OPEN = (WPS), + WIFI_SECURITY_WPS_SECURE = (WPS | AES), + + WIFI_SECURITY_UNKNOWN = -1, +} wifi_security_t; + +/** + * @brief Scanning parameters + * + * Used to request a scan and get results as well + */ +struct wifi_req_params { + + /** Current channel in use as a result */ + u16_t channel; + + char *ap_name; + char *password; + wifi_security_t security; +} __packed; + +/* This not meant to be used by any code but 802.15.4 L2 stack */ +struct wifi_context { + struct wifi_req_params *scan_ctx; + char *ap_name; + wifi_security_t security; +} S__packed; + + +struct wifi_api { + /** + * Mandatory to get in first position. + * A network device should indeed provide a pointer on such + * net_if_api structure. So we make current structure pointer + * that can be casted to a net_if_api structure pointer. + */ + struct net_if_api iface_api; + + /** scan available access points */ + int (*scan)(struct device *dev); + + /** Connect to access point */ + int (*ap_connect)(struct device *dev, char *ssid, + wifi_security_t sec_type, char *psk); + + /** Disconnect from access point */ + int (*ap_disconnect)(struct device *dev); +} __packed; + +#endif /* __WIFI_MGMT_H__ */ diff --git a/subsys/net/ip/Kconfig.mgmt b/subsys/net/ip/Kconfig.mgmt index 2d36dedfe6072..32141a074d4eb 100644 --- a/subsys/net/ip/Kconfig.mgmt +++ b/subsys/net/ip/Kconfig.mgmt @@ -65,4 +65,11 @@ config NET_DEBUG_MGMT_EVENT_STACK help Add debug messages output on how much Net MGMT event stack is used. +config NET_MGMT_WIFI + bool "Enable wifi management module" + default n + depends on NET_MGMT_EVENT + help + Enables support for wifi management functions + endif diff --git a/subsys/net/ip/Makefile b/subsys/net/ip/Makefile index fb852587d61aa..822662f53bb9a 100644 --- a/subsys/net/ip/Makefile +++ b/subsys/net/ip/Makefile @@ -20,6 +20,7 @@ obj-$(CONFIG_NET_MGMT_EVENT) += net_mgmt.o obj-$(CONFIG_NET_TCP) += tcp.o obj-$(CONFIG_NET_SHELL) += net_shell.o obj-$(CONFIG_NET_STATISTICS) += net_stats.o +obj-$(CONFIG_NET_MGMT_WIFI) += wifi_mgmt.o ifeq ($(CONFIG_NET_UDP),y) obj-$(CONFIG_NET_UDP) += connection.o diff --git a/subsys/net/ip/wifi_mgmt.c b/subsys/net/ip/wifi_mgmt.c new file mode 100644 index 0000000000000..25254be03bed2 --- /dev/null +++ b/subsys/net/ip/wifi_mgmt.c @@ -0,0 +1,109 @@ +/* + * Copyright (c) 2017 ipTronix S.r.l. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +#include + +#include +#include + +static int wifi_scan(u32_t mgmt_request, struct net_if *iface, + void *data, size_t len) +{ + struct wifi_api *wifi = + (struct wifi_api *)iface->dev->driver_api; + struct wifi_context *ctx = + (struct wifi_context *)net_if_get_device(iface)->driver_data; + struct wifi_req_params *scan = + (struct wifi_req_params *)data; + int ret; + + NET_DBG("WiFi scan requested"); + + if (ctx->scan_ctx) { + return -EALREADY; + } + + ctx->scan_ctx = scan; + ret = 0; + + if (wifi->scan(iface->dev)) { + NET_DBG("Could not start scanning"); + ret = -EIO; + + goto out; + } + +out: + ctx->scan_ctx = NULL; + + return ret; +} + +NET_MGMT_REGISTER_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_AP_SCAN, + wifi_scan); + +static int wifi_ap_connect(u32_t mgmt_request, struct net_if *iface, + void *data, size_t len) +{ + struct wifi_api *wifi = + (struct wifi_api *)iface->dev->driver_api; + struct wifi_context *ctx = + (struct wifi_context *)net_if_get_device(iface)->driver_data; + struct wifi_req_params *req = + (struct wifi_req_params *)data; + + NET_DBG("connection requested to SSID: %s", req->ap_name); + + if (ctx->scan_ctx) { + /* TODO: stop scanning if necessary */ + } + + if (wifi->ap_connect(iface->dev, req->ap_name, req->security, + req->password)) { + NET_DBG("Could not connect"); + return -EIO; + } + + ctx->ap_name = req->ap_name; + ctx->security = req->security; + + return 0; +} + +NET_MGMT_REGISTER_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_AP_CONNECT, + wifi_ap_connect); + +static int wifi_ap_disconnect(u32_t mgmt_request, struct net_if *iface, + void *data, size_t len) +{ + struct wifi_api *wifi = + (struct wifi_api *)iface->dev->driver_api; + struct wifi_context *ctx = + (struct wifi_context *)net_if_get_device(iface)->driver_data; + int ret; + + NET_DBG("disconnection requested"); + + ret = 0; + + if (wifi->ap_disconnect(iface->dev)) { + NET_DBG("Could not disconnect"); + ret = -EIO; + + goto out; + } + + ctx->ap_name = NULL; + ctx->security = WIFI_SECURITY_UNKNOWN; + +out: + return ret; +} + +NET_MGMT_REGISTER_REQUEST_HANDLER(NET_REQUEST_WIFI_CMD_AP_DISCONNECT, + wifi_ap_disconnect);