Merge pull request #13754 from gschorcht/drivers/atwinc15x0

drivers: add ATWINC15x0 WiFi netdev driver
This commit is contained in:
Alexandre Abadie 2020-06-26 15:46:02 +02:00 committed by GitHub
commit 81b7709ee3
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
37 changed files with 2839 additions and 4 deletions

View File

@ -1,3 +1,7 @@
USEMODULE += boards_common_arduino-mkr
ifneq (,$(filter gnrc_netdev_default,$(USEMODULE)))
USEMODULE += atwinc15x0
endif
include $(RIOTBOARD)/common/arduino-mkr/Makefile.dep

View File

@ -50,6 +50,18 @@ extern "C" {
#define LED0_NAME "LED(Green)"
/** @} */
/**
* @name Board configuration for ATWINC15x0 WiFi netdev driver
* @{
*/
#define ATWINC15X0_PARAM_SPI SPI_DEV(1)
#define ATWINC15X0_PARAM_SSN_PIN GPIO_PIN(0, 14)
#define ATWINC15X0_PARAM_RESET_PIN GPIO_PIN(0, 27)
#define ATWINC15X0_PARAM_CHIP_EN_PIN GPIO_PIN(0, 28)
#define ATWINC15X0_PARAM_WAKE_PIN GPIO_PIN(1, 8)
#define ATWINC15X0_PARAM_IRQ_PIN GPIO_PIN(1, 9)
/** @} */
#ifdef __cplusplus
}
#endif

View File

@ -2,6 +2,12 @@ ifneq (,$(filter saul_default,$(USEMODULE)))
USEMODULE += saul_gpio
endif
ifneq (,$(filter feather-m0-wifi,$(USEMODULE)))
ifneq (,$(filter gnrc_netdev_default netdev_default,$(USEMODULE)))
USEMODULE += atwinc15x0
endif
endif
# use arduino-bootloader only if no other stdio_% other than stdio_cdc_acm
# is requested
ifeq (,$(filter-out stdio_cdc_acm,$(filter stdio_% slipdev_stdio,$(USEMODULE))))

View File

@ -1,3 +1,5 @@
PSEUDOMODULES += feather-m0-wifi
PORT_LINUX ?= /dev/ttyACM0
PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.usbmodem*)))

View File

@ -12,10 +12,10 @@ All the feather M0 boards are built based on the same Atmel SAMD21G18A
microcontroller. See @ref cpu_samd21.
Several types of Feather M0 boards exist:
* [Feather M0 WiFi](https://learn.adafruit.com/adafruit-feather-m0-wifi-atwinc1500/)
* [Feather M0 BLE](https://learn.adafruit.com/adafruit-feather-m0-bluefruit-le/overview)
* [Feather M0 Adalogger](https://learn.adafruit.com/adafruit-feather-m0-adalogger/)
* [Feather M0 LoRa](https://learn.adafruit.com/adafruit-feather-m0-radio-with-lora-radio-module)
- [Feather M0 WiFi](https://learn.adafruit.com/adafruit-feather-m0-wifi-atwinc1500/)
- [Feather M0 BLE](https://learn.adafruit.com/adafruit-feather-m0-bluefruit-le/overview)
- [Feather M0 Adalogger](https://learn.adafruit.com/adafruit-feather-m0-adalogger/)
- [Feather M0 LoRa](https://learn.adafruit.com/adafruit-feather-m0-radio-with-lora-radio-module)
The different modules used to differentiate the boards (ATWINC1500 WiFi,
Bluefruit LE, SD card, LoRa) are connected via SPI (SPI_DEV(0)) to the
@ -52,6 +52,20 @@ Example with `hello-world` application:
bootloader mode by double tapping the reset button before running the
flash command.
### Using the WiFi interface
To enable the WiFi interface of the Feather M0 WiFi variant of the board
automatically for networking applications, add `USEMODULE=atwin1x0` to
the `make` command and define the required parameters, for example:
```
USEMODULE='feather-m0-wifi' \
CFLAGS='-DWIFI_SSID=\"<ssid>\" -DWIFI_PASS=\"<pass>\"' \
make BOARD=feather-m0 -C examples/gnrc_networking
```
For detailed information about the parameters, see section
@ref drivers_atwinc15x0.
### Accessing STDIO via UART
STDIO of RIOT is directly available over the USB port.

View File

@ -42,6 +42,18 @@ extern "C" {
#define LED0_TOGGLE (LED_PORT.OUTTGL.reg = LED0_MASK)
/** @} */
/**
* @name Configuration for Feather M0 WiFi and the ATWINC15x0 WiFi netdev
* @{
*/
#define ATWINC15X0_PARAM_SPI SPI_DEV(0)
#define ATWINC15X0_PARAM_SSN_PIN GPIO_PIN(0, 6)
#define ATWINC15X0_PARAM_RESET_PIN GPIO_PIN(0, 8)
#define ATWINC15X0_PARAM_CHIP_EN_PIN GPIO_PIN(0, 14)
#define ATWINC15X0_PARAM_IRQ_PIN GPIO_PIN(0, 21)
#define ATWINC15X0_PARAM_WAKE_PIN GPIO_UNDEF
/** @} */
/**
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
*/

View File

@ -118,6 +118,16 @@ ifneq (,$(filter ata8520e,$(USEMODULE)))
FEATURES_REQUIRED += periph_spi
endif
ifneq (,$(filter atwinc15x0,$(USEMODULE)))
USEMODULE += luid
USEMODULE += netdev_eth
USEMODULE += xtimer
USEPKG += driver_atwinc15x0
FEATURES_REQUIRED += periph_gpio
FEATURES_REQUIRED += periph_gpio_irq
FEATURES_REQUIRED += periph_spi
endif
ifneq (,$(filter bh1750fvi,$(USEMODULE)))
USEMODULE += xtimer
FEATURES_REQUIRED += periph_i2c

View File

@ -48,6 +48,10 @@ ifneq (,$(filter ata8520e,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/ata8520e/include
endif
ifneq (,$(filter atwinc15x0,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/atwinc15x0/include
endif
ifneq (,$(filter bh1750fvi,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/bh1750fvi/include
endif

View File

@ -0,0 +1 @@
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,98 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_atwinc15x0
* @{
*
* @file
* @brief RIOT BSP API implementation
*
* @author Gunar Schorcht <gunar@schorcht.net>
*
* @}
*/
#include "atwinc15x0_internal.h"
#include "mutex.h"
#include "periph/spi.h"
#include "xtimer.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
void atwinc15x0_isr(void *arg)
{
(void)arg;
if (atwinc15x0->bsp_isr != NULL && atwinc15x0->bsp_irq_enabled) {
atwinc15x0->bsp_isr();
}
atwinc15x0_irq();
}
sint8 nm_bsp_init(void)
{
assert(atwinc15x0);
assert(atwinc15x0->params.reset_pin != GPIO_UNDEF);
assert(atwinc15x0->params.irq_pin != GPIO_UNDEF);
gpio_init(atwinc15x0->params.reset_pin, GPIO_OUT);
gpio_set(atwinc15x0->params.reset_pin);
gpio_init_int(atwinc15x0->params.irq_pin, GPIO_IN_PU, GPIO_FALLING,
atwinc15x0_isr, NULL);
if (atwinc15x0->params.chip_en_pin != GPIO_UNDEF) {
gpio_init(atwinc15x0->params.chip_en_pin, GPIO_OUT);
gpio_set(atwinc15x0->params.chip_en_pin);
}
if (atwinc15x0->params.wake_pin != GPIO_UNDEF) {
gpio_init(atwinc15x0->params.wake_pin, GPIO_OUT);
gpio_set(atwinc15x0->params.wake_pin);
}
return 0;
}
sint8 nm_bsp_deinit(void)
{
return 0;
}
void nm_bsp_reset(void)
{
assert(atwinc15x0);
gpio_clear(atwinc15x0->params.reset_pin);
nm_bsp_sleep(100);
gpio_set(atwinc15x0->params.reset_pin);
nm_bsp_sleep(100);
}
void nm_bsp_sleep(uint32 u32TimeMsec)
{
xtimer_usleep(u32TimeMsec * US_PER_MS);
}
void nm_bsp_register_isr(tpfNmBspIsr pfIsr)
{
assert(atwinc15x0);
DEBUG("%s %p\n", __func__, pfIsr);
atwinc15x0->bsp_isr = pfIsr;
}
void nm_bsp_interrupt_ctrl(uint8 u8Enable)
{
assert(atwinc15x0);
DEBUG("%s %u\n", __func__, u8Enable);
atwinc15x0->bsp_irq_enabled = u8Enable;
}

View File

@ -0,0 +1,88 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_atwinc15x0
* @{
*
* @file
* @brief RIOT bus wrapper API implementation
*
* @author Gunar Schorcht <gunar@schorcht.net>
*
* @}
*/
#include "atwinc15x0_internal.h"
#include "bus_wrapper/include/nm_bus_wrapper.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
#define NM_BUS_MAX_TRX_SZ 256
tstrNmBusCapabilities egstrNmBusCapabilities =
{
NM_BUS_MAX_TRX_SZ
};
sint8 nm_bus_init(void *arg)
{
(void)arg;
assert(atwinc15x0);
assert(atwinc15x0->params.ssn_pin != GPIO_UNDEF);
gpio_init(atwinc15x0->params.ssn_pin, GPIO_OUT);
gpio_set(atwinc15x0->params.ssn_pin);
nm_bsp_reset();
nm_bsp_sleep(1);
return 0;
}
sint8 nm_bus_ioctl(uint8 cmd, void* params)
{
assert(atwinc15x0);
sint8 res = 0;
tstrNmSpiRw *spi_params = (tstrNmSpiRw *)params;
switch (cmd)
{
case NM_BUS_IOCTL_RW:
spi_acquire(atwinc15x0->params.spi, atwinc15x0->params.ssn_pin,
SPI_MODE_0, atwinc15x0->params.spi_clk);
spi_transfer_bytes(atwinc15x0->params.spi,
atwinc15x0->params.ssn_pin, 0,
spi_params->pu8InBuf,
spi_params->pu8OutBuf,
spi_params->u16Sz);
spi_release(atwinc15x0->params.spi);
break;
default:
res = M2M_ERR_BUS_FAIL;
DEBUG("invalid ioctl cmd\n");
break;
}
return res;
}
sint8 nm_bus_deinit(void)
{
return 0;
}
sint8 nm_bus_reinit(void *arg)
{
(void)arg;
return 0;
}

View File

@ -0,0 +1,524 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_atwinc15x0
* @{
*
* @file
* @brief Netdev driver for the ATWINC15x0 WiFi module
*
* @author Gunar Schorcht <gunar@schorcht.net>
*
* @}
*/
#include <string.h>
#define ETH_MODE (1)
#include "atwinc15x0_internal.h"
#include "atwinc15x0_params.h"
#include "bus_wrapper/include/nm_bus_wrapper.h"
#include "driver/source/m2m_hif.h"
#include "driver/include/m2m_wifi.h"
#include "assert.h"
#include "log.h"
#include "net/netdev/eth.h"
#include "od.h"
#include "xtimer.h"
#define ENABLE_DEBUG (0)
#define ENABLE_DEBUG_DUMP (0)
#include "debug.h"
#define ATWINC15X0_MAC_STR "%02x:%02x:%02x:%02x:%02x:%02x"
#define ATWINC15X0_MAC_STR_ARG(m) m[0], m[1], m[2], m[3], m[4], m[5]
#define ATWINC15X0_WAIT_TIME (1 * US_PER_MS)
#define ATWINC15X0_WAIT_TIMEOUT (20)
#define ATWINC15X0_WAIT_RECONNECT (5 * US_PER_SEC)
/* Forward function declarations */
static void _atwinc15x0_wifi_cb(uint8_t event, void *msg);
static void _atwinc15x0_eth_cb(uint8_t type, void *msg, void *ctrl);
static int _atwinc15x0_connect(void);
/**
* The following buffer is required by the ATWINC15x0 vendor driver to store
* packets received from the ATWINC15x0 WiFI module in it. Its size has to be
* at least one Ethernet frame of maximum length.
*
* The event-driven handling of incoming packets is strictly sequential in
* the context of the `netif` thread. This means that an incoming packet
* is first received by the `netif` thread and copied to its packet buffer
* before the next event of an incoming packet is handled by the ATWINC15x0
* vendor driver. It can therefore be assumed that only one received packet
* can be in the buffer at a time. No further separate intermediate buffer
* is required.
*
* Furthermore, this buffer can be used for preparing a packet to be sent,
* since it can be assumed that receiving and sending packets are implicitly
* mutually exclusive due to their strictly sequential processing.
*/
static uint8_t atwinc15x0_eth_buf[ETHERNET_MAX_LEN];
/* ATWINC15x0 vendor driver initialization structure (can't be const) */
static tstrWifiInitParam atwinc15x0_wifi_params = {
.pfAppWifiCb = _atwinc15x0_wifi_cb,
.strEthInitParam = {
.pfAppWifiCb = _atwinc15x0_wifi_cb,
.pfAppEthCb = _atwinc15x0_eth_cb,
.au8ethRcvBuf = atwinc15x0_eth_buf,
.u16ethRcvBufSize = ARRAY_SIZE(atwinc15x0_eth_buf),
.u8EthernetEnable = M2M_WIFI_MODE_ETHERNET,
},
};
/**
* Reference to the single ATWINC15x0 device instance
*
* Since the vendor ATWINC15x0 host driver uses many global variables, only
* a single ATWINC15x0 device can be used. Therefore, the RIOT driver only
* supports a single instance of an ATWINC15x0 device. The reference is
* needed in callback functions where a reference to the device is not
* available.
*/
atwinc15x0_t *atwinc15x0 = NULL;
static void _atwinc15x0_eth_cb(uint8_t type, void *msg, void *ctrl_buf)
{
assert(atwinc15x0);
assert(msg != NULL);
assert(ctrl_buf != NULL);
tstrM2mIpCtrlBuf *ctrl = (tstrM2mIpCtrlBuf *)ctrl_buf;
DEBUG("%s type=%u msg=%p len=%d remaining=%d\n", __func__,
type, msg, ctrl->u16DataSize, ctrl->u16RemainigDataSize);
#if MODULE_OD && ENABLE_DEBUG_DUMP
od_hex_dump(msg, ctrl->u16DataSize, 16);
#endif
/* the buffer shouldn't be used here */
assert(atwinc15x0->rx_buf == NULL);
uint32_t state = irq_disable();
atwinc15x0->rx_buf = msg;
atwinc15x0->rx_len = ctrl->u16DataSize;
irq_restore(state);
/**
* This function is executed in the thread context. Therefore
* netdev.event_callback can be called directly, which avoids an
* additional intermediate buffer.
*/
atwinc15x0->netdev.event_callback(&atwinc15x0->netdev,
NETDEV_EVENT_RX_COMPLETE);
}
typedef union {
tstrM2mWifiStateChanged state_changed;
tstrM2MConnInfo conn_info;
tstrM2mScanDone scan_done;
tstrM2mWifiscanResult scan_result;
int8_t rssi;
} atwinc15x0_event_t;
static bool _rssi_info_ready = false;
static void _atwinc15x0_wifi_cb(uint8_t type, void *msg)
{
/**
* This function is executed in thread context. There is no need to call
* netdev_trigger_event_isr and to handle the events in _atwinc15x0_isr
*/
DEBUG("%s %u %p\n", __func__, type, msg);
atwinc15x0_event_t* event = (atwinc15x0_event_t *)msg;
switch (type) {
case M2M_WIFI_RESP_SCAN_DONE:
DEBUG("%s scan done, %d APs found\n", __func__,
event->scan_done.u8NumofCh);
/* read the first scan result record */
m2m_wifi_req_scan_result(0);
break;
case M2M_WIFI_RESP_SCAN_RESULT:
LOG_DEBUG("[atwinc15x0] %s: rssi %d, auth %d, ch %d, bssid "
ATWINC15X0_MAC_STR "\n",
event->scan_result.au8SSID,
event->scan_result.s8rssi,
event->scan_result.u8AuthType,
event->scan_result.u8ch,
ATWINC15X0_MAC_STR_ARG(event->scan_result.au8BSSID));
if (memcmp(&event->scan_result.au8BSSID,
&atwinc15x0->ap, ETHERNET_ADDR_LEN) == 0) {
/* use the results for current AP to set the current channel */
atwinc15x0->channel = event->scan_result.u8ch;
}
if (event->scan_result.u8index < m2m_wifi_get_num_ap_found()) {
/* read the next scan result record */
m2m_wifi_req_scan_result(event->scan_result.u8index + 1);
}
break;
case M2M_WIFI_RESP_CON_STATE_CHANGED:
switch (event->state_changed.u8CurrState) {
case M2M_WIFI_DISCONNECTED:
LOG_INFO("[atwinc15x0] WiFi disconnected\n");
atwinc15x0->connected = false;
atwinc15x0->netdev.event_callback(&atwinc15x0->netdev,
NETDEV_EVENT_LINK_DOWN);
/* wait and try to reconnect */
xtimer_usleep(ATWINC15X0_WAIT_RECONNECT);
_atwinc15x0_connect();
break;
case M2M_WIFI_CONNECTED:
LOG_INFO("[atwinc15x0] WiFi connected\n");
atwinc15x0->connected = true;
atwinc15x0->netdev.event_callback(&atwinc15x0->netdev,
NETDEV_EVENT_LINK_UP);
/* get information about the current AP */
m2m_wifi_get_connection_info();
/* start a scan for additional info, e.g. used channel */
m2m_wifi_request_scan(M2M_WIFI_CH_ALL);
break;
default:
break;
}
break;
case M2M_WIFI_RESP_CONN_INFO:
DEBUG("%s conn info %s, rssi %d, sec %u, bssid "
ATWINC15X0_MAC_STR "\n", __func__,
event->conn_info.acSSID,
event->conn_info.s8RSSI,
event->conn_info.u8SecType,
ATWINC15X0_MAC_STR_ARG(event->conn_info.au8MACAddress));
/* set the RSSI and BSSID of the current AP */
atwinc15x0->rssi = event->conn_info.s8RSSI;
memcpy(atwinc15x0->ap,
event->conn_info.au8MACAddress, ETHERNET_ADDR_LEN);
break;
case M2M_WIFI_RESP_CURRENT_RSSI:
DEBUG("%s current rssi %d\n", __func__, event->rssi);
/* set the RSSI */
atwinc15x0->rssi = event->rssi;
_rssi_info_ready = true;
break;
default:
break;
}
}
static int _atwinc15x0_send(netdev_t *netdev, const iolist_t *iolist)
{
atwinc15x0_t *dev = (atwinc15x0_t *)netdev;
assert(dev);
assert(dev == atwinc15x0);
assert(iolist);
if (!dev->connected) {
DEBUG("%s WiFi is still not connected to AP, cannot send", __func__);
return -ENODEV;
}
/* atwinc15x0_eth_buf should not be used for incoming packets here */
assert(dev->rx_buf == NULL);
uint32_t state = irq_disable();
uint16_t tx_len = 0;
/* load packet data into the buffer */
for (const iolist_t *iol = iolist; iol; iol = iol->iol_next) {
if (tx_len + iol->iol_len > ETHERNET_MAX_LEN) {
irq_restore(state);
return -EOVERFLOW;
}
if (iol->iol_len) {
memcpy (atwinc15x0_eth_buf + tx_len, iol->iol_base, iol->iol_len);
tx_len += iol->iol_len;
}
}
#if ENABLE_DEBUG
DEBUG("%s send %d byte", __func__, tx_len);
#if MODULE_OD && ENABLE_DEBUG_DUMP
od_hex_dump(dev->tx_buf, dev->tx_len, OD_WIDTH_DEFAULT);
#endif /* MODULE_OD && ENABLE_DEBUG_HEXDUMP */
#endif
irq_restore(state);
/* send the the packet */
if (m2m_wifi_send_ethernet_pkt(atwinc15x0_eth_buf, tx_len) == M2M_SUCCESS) {
netdev->event_callback(netdev, NETDEV_EVENT_TX_COMPLETE);
return tx_len;
}
else {
DEBUG("%s sending WiFi packet failed", __func__);
return -EIO;
}
}
static int _atwinc15x0_recv(netdev_t *netdev, void *buf, size_t len, void *info)
{
atwinc15x0_t *dev = (atwinc15x0_t *)netdev;
(void)info;
assert(dev);
assert(dev == atwinc15x0);
uint32_t state = irq_disable();
uint16_t rx_size = dev->rx_len;
if (!rx_size) {
/* there is nothing in receive buffer */
irq_restore(state);
return 0;
}
if (!buf) {
/* get the size of the frame */
if (len > 0) {
/* if len > 0, drop the frame */
dev->rx_len = 0;
dev->rx_buf = NULL;
}
irq_restore(state);
return rx_size;
}
if (len < rx_size) {
/* buffer is smaller than the number of received bytes */
DEBUG("%s not enough space in receive buffer", __func__);
/* newest API requires to drop the frame in that case */
dev->rx_len = 0;
dev->rx_buf = NULL;
irq_restore(state);
return -ENOBUFS;
}
/* remove length bytes, copy received packet to buffer */
memcpy(buf, dev->rx_buf, dev->rx_len);
dev->rx_len = 0;
dev->rx_buf = NULL;
#if ENABLE_DEBUG
ethernet_hdr_t *hdr = (ethernet_hdr_t *)buf;
DEBUG("%s received %u byte from addr " ATWINC15X0_MAC_STR "\n",
__func__, rx_size, ATWINC15X0_MAC_STR_ARG(hdr->src));
#if MODULE_OD && ENABLE_DEBUG_DUMP
od_hex_dump(buf, rx_size, OD_WIDTH_DEFAULT);
#endif /* MODULE_OD && ENABLE_DEBUG_HEXDUMP */
#endif /* ENABLE_DEBUG */
irq_restore(state);
return rx_size;
}
static int _atwinc15x0_get(netdev_t *netdev, netopt_t opt, void *val,
size_t max_len)
{
atwinc15x0_t *dev = (atwinc15x0_t *)netdev;
(void)max_len;
assert(val);
assert(dev);
assert(dev == atwinc15x0);
DEBUG("%s dev=%p opt=%u val=%p max_len=%u\n", __func__,
netdev, opt, val, max_len);
switch (opt) {
case NETOPT_IS_WIRED:
return -ENOTSUP;
case NETOPT_ADDRESS:
assert(max_len >= ETHERNET_ADDR_LEN);
uint8_t valid;
m2m_wifi_get_otp_mac_address((uint8_t *)val, &valid);
return (valid) ? ETHERNET_ADDR_LEN : 0;
case NETOPT_LINK:
assert(max_len == sizeof(netopt_enable_t));
*((netopt_enable_t *)val) = (dev->connected) ? NETOPT_ENABLE
: NETOPT_DISABLE;
return sizeof(netopt_enable_t);
case NETOPT_CHANNEL:
assert(max_len == sizeof(uint16_t));
*((uint16_t *)val) = dev->channel;
return sizeof(uint16_t);
case NETOPT_RSSI:
assert(max_len == sizeof(int8_t));
_rssi_info_ready = false;
/* trigger the request current RSSI (asynchronous function) */
if (m2m_wifi_req_curr_rssi() != M2M_SUCCESS) {
return 0;
}
/* wait for the response with a given timeout */
unsigned int _rssi_info_time_out = ATWINC15X0_WAIT_TIMEOUT;
while (!_rssi_info_ready && _rssi_info_time_out--) {
xtimer_usleep(ATWINC15X0_WAIT_TIME);
}
/* return the RSSI */
*((int8_t *)val) = dev->rssi;
return sizeof(int8_t);
default:
return netdev_eth_get(netdev, opt, val, max_len);
}
}
static int _atwinc15x0_set(netdev_t *netdev, netopt_t opt, const void *val,
size_t max_len)
{
assert(val);
DEBUG("%s dev=%p opt=%u val=%p max_len=%u\n", __func__,
netdev, opt, val, max_len);
switch (opt) {
case NETOPT_ADDRESS:
assert(max_len == ETHERNET_ADDR_LEN);
m2m_wifi_set_mac_address((uint8_t *)val);
return ETHERNET_ADDR_LEN;
default:
return netdev_eth_set(netdev, opt, val, max_len);
}
}
static int _atwinc15x0_init(netdev_t *netdev)
{
atwinc15x0_t *dev = (atwinc15x0_t *)netdev;
(void)netdev;
assert(dev);
assert(dev == atwinc15x0);
DEBUG("%s dev=%p\n", __func__, dev);
atwinc15x0->bsp_isr = NULL;
atwinc15x0->bsp_irq_enabled = true;
atwinc15x0->connected = false;
atwinc15x0->rx_len = 0;
atwinc15x0->rx_buf = NULL;
nm_bsp_init();
int8_t res;
/* initialize the WINC Driver*/
if ((res = m2m_wifi_init(&atwinc15x0_wifi_params)) != M2M_SUCCESS) {
DEBUG("m2m_wifi_init failed with code %d\n", res);
if (res == M2M_ERR_FW_VER_MISMATCH) {
LOG_WARNING("[atwinc15x0] Firmware version mismatch, "
"this may lead to problems.\n");
}
else {
LOG_ERROR("[atwinc15x0] Driver initialization error %d\n", res);
return res;
}
}
/* disable the built-in DHCP client */
if ((res = m2m_wifi_enable_dhcp(false)) != M2M_SUCCESS) {
LOG_ERROR("[atwinc15x0] m2m_wifi_enable_dhcp failed with %d\n", res);
return res;
}
/* try to connect and return */
return _atwinc15x0_connect();
}
static int _atwinc15x0_connect(void)
{
tuniM2MWifiAuth auth_info;
tenuM2mSecType auth_type = M2M_WIFI_SEC_OPEN;
#if !defined(MODULE_WIFI_ENTERPRISE) && defined(WIFI_PASS)
strncpy((char *)auth_info.au8PSK, WIFI_PASS, M2M_MAX_PSK_LEN);
auth_type = M2M_WIFI_SEC_WPA_PSK;
#elif defined(MODULE_WIFI_ENTERPRISE)
#if defined(WIFI_USER) && defined(WIFI_PASS)
strncpy((char *)&auth_info.strCred1x.au8UserName, WIFI_USER, M2M_1X_USR_NAME_MAX);
strncpy((char *)&auth_info.strCred1x.au8Passwd, WIFI_PASS, M2M_1X_PWD_MAX);
auth_type = M2M_WIFI_SEC_802_1X;
#else /* defined(WIFI_EAP_USER) && defined(WIFI_EAP_PASS) */
#error WIFI_EAP_USER and WIFI_EAP_PASS have to define the user name \
and the password for EAP phase 2 authentication in wifi_enterprise
#endif /* defined(WIFI_EAP_USER) && defined(WIFI_EAP_PASS) */
#endif /* defined(MODULE_ESP_WIFI_ENTERPRISE) */
/* connect */
int8_t res;
if ((res = m2m_wifi_connect(WIFI_SSID, sizeof(WIFI_SSID),
auth_type, &auth_info,
M2M_WIFI_CH_ALL)) != M2M_SUCCESS) {
LOG_ERROR("[atwinc15x0] WiFi connect failed with %d\n", res);
return res;
}
return 0;
}
static void _atwinc15x0_isr(netdev_t *netdev)
{
atwinc15x0_t *dev = (atwinc15x0_t *)netdev;
assert(dev);
assert(dev == atwinc15x0);
DEBUG("%s dev=%p\n", __func__, dev);
/* handle pending ATWINC15x0 module events */
while (m2m_wifi_handle_events(NULL) != M2M_SUCCESS) { }
}
const netdev_driver_t atwinc15x0_netdev_driver = {
.send = _atwinc15x0_send,
.recv = _atwinc15x0_recv,
.init = _atwinc15x0_init,
.isr = _atwinc15x0_isr,
.get = _atwinc15x0_get,
.set = _atwinc15x0_set,
};
void atwinc15x0_setup(atwinc15x0_t *dev, const atwinc15x0_params_t *params)
{
assert(dev);
atwinc15x0 = dev;
atwinc15x0->netdev.driver = &atwinc15x0_netdev_driver;
atwinc15x0->params = *params;
}
void atwinc15x0_irq(void)
{
if (atwinc15x0) {
netdev_trigger_event_isr(&atwinc15x0->netdev);
}
}

174
drivers/atwinc15x0/doc.txt Normal file
View File

@ -0,0 +1,174 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup drivers_atwinc15x0 ATWINC15x0 WiFi module driver
* @ingroup drivers_netdev
* @brief Network device driver for the Microchip ATWINC15x0 WiFi Module
*
* @author Gunar Schorcht <gunar@schorcht.net>
### Introduction
This module implements a `netdev` device driver for the Microchip ATWINC15x0
WiFi module. The ATWINC15x0 WiFi module is widely used as WiFi interface on
various boards and extension boards. Examples are:
- [Adafruit Feather M0 WiFi](https://learn.adafruit.com/adafruit-feather-m0-wifi-atwinc1500/)
(also supported by [RIOT](https://doc.riot-os.org/group__boards__feather-m0.html))
- [ATWIN1500-XPRO](https://www.microchip.com/DevelopmentTools/ProductDetails/ATWINC1500-XPRO)
for the extension of Atmel Xplained PRO boards (also supported by RIOT)
- [Adafruit ATWINC1500 WiFi breakout](https://learn.adafruit.com/adafruit-atwinc1500-wifi-module-breakout)
- [Watterott ATWINC1500-Breakout](https://github.com/watterott/ATWINC1500-Breakout)
Since the ATWINC15x0 WiFi module is also the only module supported by the
standard [Arduino WiFi101 library](https://github.com/arduino-libraries/WiFi101),
there are a number of Arduino shields with the ATWINC15x0 WiFi module, e.g.
[Adafruit WINC1500 WiFi Shield for Arduino](https://learn.adafruit.com/adafruit-winc1500-wifi-shield-for-arduino).
Using this 'netdev' driver together with an ATWINC15x0 WiFi module enables
the connection via WiFi in RIOT.
### Microchip ATWINC15x0 WiFi module
The ATWINC15x0 WiFi module is a low-power IEEE 802.11 b/g/n module with a
bandwidth of 20 MHz in the 2,4 GHz ISM band. It supports the IEEE 802.11i/WPA2
personal and enterprise modes. In enterprise mode it supports
- EAP-TLS
- EAP-PEAPv0/1 with TLS
- EAP-TTLSv0 with MSCHAPv2
- EAP-PEAPv0/1 with MSCHAPv2
The WiFi module ATWINC15x0 is connected via SPI and supports SPI clock speeds
of up to 48 MHz. Although the module also has an I2C and a UART interface,
these interfaces are only used for debugging.
The ATWINC15x0 WiFi module implements a complete TCP/IP procotol stack which is
not used in RIOT.
### Driver Details
The ATWINC15x0 WiFi `netdev` driver doesn't directly use the ATWINC15x0 WiFi
module. Instead, it uses the ATWINC15x0 vendor driver
[WINC1500 Wifi](http://asf.atmel.com/docs/latest/sam4s/html/group__winc1500__group.html).
from Microchip's Advanced Software Framework. For that purpose, the
[Arduino WiFi101 library](https://github.com/arduino-libraries/WiFi101) which
also includes this vendor library is used as a package.
Although the ATWINC15x0 vendor driver is complex and quite large, there is
no other way to do it because the ATWINC15x0 WiFi module's programming
interface is not documented. At the very least, the ATWINC15x0 WiFi `netdev`
driver uses only those parts of the vendor driver that are absolutely
necessary.
The ATWINC15x0 vendor driver consists of several parts:
- the M2M WiFi library, which implements high-level WiFi connection management
Functions
- the HIF (Host Interface) library, which implements the interface with the
ATWINC15x0 module
- the BSP (Bus Support Package) as an abstraction layer for platform-specific
Functions
- the bus wrapper interface for access to the SPI
In addition to these parts, the ATWINC15x0 vendor driver contains a
socket library and a library for accessing the SPI flash of the ATWINC15x0
module, but these are not used in RIOT.
The ATWINC15x0 WiFi `netdev` driver replaces the BSP and the Bus Wrapper
Interface by RIOT specific parts and interacts with ATWINC15x0 vendor driver
as shown in the following figure.
```
+-----------------+ +---------------+ +----------+ +------------+
| RIOT ATWINC15x0 | | ATWINC15x0 | | RIOT Bus | | ATWINC15x0 |
| netdev driver | | vendor driver | | Wrapper | | module |
+-----------------+ +---------------+ +----------+ +------------+
| | | |
| m2m_wifi_func | command | SPI(command) |
|------------------------->|--------------->|--------------->|
| return | | |
|<-------------------------| | |
| | | |
| | | |
| | | |
|<------------------------------- IRQ -----------------------|
| | | |
| m2m_wifi_handle_events | request | SPI(request) |
|------------------------->|--------------->|--------------->|
| | response | SPI(response) |
| atwinc15x0_wifi_cb |<---------------|<---------------|
|<-------------------------| | |
| | | |
| | | |
| | | |
| | | |
|<------------------------------- IRQ -----------------------|
| | | |
| m2m_wifi_handle_events | request | SPI(request) |
|------------------------->|--------------->|--------------->|
| | response | SPI(response) |
| atwinc15x0_eth_cb |<---------------|<---------------|
|<-------------------------| | |
```
As shown, the ATWINC15x0 WiFi module operates asynchronously. This means
that when an API function of the ATWINC15x0 driver is called, it simply
sends a command to the ATWINC15x0 WiFi module and returns immediately.
The command is then executed asynchronously by the ATWINC15x0 WiFi module.
As soon as the execution of the command is completed or one or more events
are pending, the module interrupts the host. Since the ISR is executed in
the interrupt context, the ATWINC15x0 'netdev' driver simply indicates
that an interrupt has occurred. The interrupt is handled later in the
thread context by calling 'm2m_wifi_handle_events'. This in turn fetches
available information from the ATWINC15x0 WiFi module and then calls
various callback functions according to the state, all of which are
executed in the thread context.
## Configuration
The ATWINC15x0 'netdev' driver requires the configuration ATWINC15x0 WiFi
module as WiFi settings:
### Hardware Configuration
The default configuration is defined in atwinc15x0_params.h and can be
overridden either by the board definition or by environment variables in
make command line.
Symbol | Default | Description
:------------------------------|:-----------------|:---------------------
`ATWINC15X0_PARAM_SPI` | `SPI_DEV(0)` | Used SPI device
`ATWINC15X0_PARAM_SPI_CLK` | `SPI_CLK_10MHZ` | Used SPI clock speed
`ATWINC15X0_PARAM_SSN_PIN` | `GPIO_PIN(1, 4)` | SPI slave select pin
`ATWINC15X0_PARAM_RESET_PIN` | `GPIO_PIN(4, 3)` | `RESET` pin
`ATWINC15X0_PARAM_IRQ_PIN` | `GPIO_PIN(7, 4)` | `IRQ` pin
`ATWINC15X0_PARAM_CHIP_EN_PIN` | `GPIO_UNDEF` | `CHIP_EN` pin
`ATWINC15X0_PARAM_WAKE_PIN` | `GPIO_UNDEF` | WAKE pin
### WiFi Configuration
At the moment only WPA2 Personal Mode is supported. The required settings are:
Parameter | Default | Description
:---------|:----------|:------------
WIFI_SSID | "RIOT_AP" | SSID of the AP to be used.
WIFI_PASS | - | Passphrase used for the AP as clear text (max. 64 chars).
The following example shows the make command with the setting of different GPIOs and the WiFi parameters.
```
USEMODULE='atwinc15x0' \
CFLAGS='-DWIFI_SSID=\"ssid\" -DWIFI_PASS=\"pass\" \
-DATWINC15X0_PARAM_SSN_PIN=GPIO_PIN\(1,6\) \
-DATWINC15X0_PARAM_RESET_PIN=GPIO_PIN\(1,4\) \
-DATWINC15X0_PARAM_IRQ_PIN=GPIO_PIN\(0,8\)' \
make BOARD=... -C examples/gnrc_networking flash term
```
*/

View File

@ -0,0 +1,47 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_atwinc15x0
* @{
*
* @file
* @brief Internal definitions for the ATWINC15x0 WiFi netdev driver
*
* @author Gunar Schorcht <gunar@schorcht.net>
*/
#ifndef ATWINC15X0_INTERNAL_H
#define ATWINC15X0_INTERNAL_H
#include "atwinc15x0.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Reference to the single ATWINC15x0 device instance
*
* Since the vendor ATWINC15x0 host driver uses many global variables, only
* a single ATWINC15x0 device can be used. Therefore, the RIOT driver only
* supports a single instance of an ATWINC15x0 device.
*/
extern atwinc15x0_t *atwinc15x0;
/**
* @brief ATWINC15x0 device driver ISR
*/
void atwinc15x0_irq(void);
#ifdef __cplusplus
}
#endif
#endif /* ATWINC15X0_INTERNAL_H */
/** @} */

View File

@ -0,0 +1,101 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_atwinc15x0
* @{
*
* @file
* @brief Default configuration for the ATWINC15x0 WiFi netdev driver
*
* @author Gunar Schorcht <gunar@schorcht.net>
*/
#ifndef ATWINC15X0_PARAMS_H
#define ATWINC15X0_PARAMS_H
#include "board.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief SSID of the AP to be used.
*/
#ifndef WIFI_SSID
#define WIFI_SSID "RIOT_AP"
#endif
/**
* @brief Passphrase used for the AP as clear text (max. 64 chars).
*/
#ifdef DOXYGEN
#define WIFI_PASS "ThisistheRIOTporttoESP"
#endif
/**
* @name Set default configuration parameters
* Pins are adapted to Arduino Mega2560 boards.
* @{
*/
#ifndef ATWINC15X0_PARAM_SPI
#define ATWINC15X0_PARAM_SPI SPI_DEV(0)
#endif
#ifndef ATWINC15X0_PARAM_SPI_CLK
#define ATWINC15X0_PARAM_SPI_CLK SPI_CLK_10MHZ
#endif
#ifndef ATWINC15X0_PARAM_SSN_PIN
#define ATWINC15X0_PARAM_SSN_PIN GPIO_PIN(1, 4) /* D10 (PB4) */
#endif
#ifndef ATWINC15X0_PARAM_RESET_PIN
#define ATWINC15X0_PARAM_RESET_PIN GPIO_PIN(4, 3) /* D5 (PE3) */
#endif
#ifndef ATWINC15X0_PARAM_IRQ_PIN
#define ATWINC15X0_PARAM_IRQ_PIN GPIO_PIN(7, 4) /* D7 (PH4) */
#endif
#ifndef ATWINC15X0_PARAM_CHIP_EN_PIN
#define ATWINC15X0_PARAM_CHIP_EN_PIN GPIO_UNDEF
#endif
#ifndef ATWINC15X0_PARAM_WAKE_PIN
#define ATWINC15X0_PARAM_WAKE_PIN GPIO_UNDEF
#endif
#ifndef ATWINC15X0_PARAMS
#define ATWINC15X0_PARAMS { \
.spi = ATWINC15X0_PARAM_SPI, \
.spi_clk = ATWINC15X0_PARAM_SPI_CLK, \
.ssn_pin = ATWINC15X0_PARAM_SSN_PIN, \
.reset_pin = ATWINC15X0_PARAM_RESET_PIN, \
.irq_pin = ATWINC15X0_PARAM_IRQ_PIN, \
.chip_en_pin = ATWINC15X0_PARAM_CHIP_EN_PIN, \
.wake_pin = ATWINC15X0_PARAM_WAKE_PIN, \
}
#endif
/** @} */
/**
* @brief Allocate some memory to store the actual configuration
*/
static const atwinc15x0_params_t atwinc15x0_params[] =
{
ATWINC15X0_PARAMS
};
#ifdef __cplusplus
}
#endif
#endif /* ATWINC15X0_PARAMS_H */
/** @} */

View File

@ -0,0 +1,50 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
#if !DOXYGEN
/**
* @ingroup drivers_atwinc15x0
* @{
*
* @file
* @brief Internal compile config for the ATWINC15x0 WiFi netdev driver
*
* @author Gunar Schorcht <gunar@schorcht.net>
*/
#ifndef BSP_INCLUDE_NM_BSP_INTERNAL_H
#define BSP_INCLUDE_NM_BSP_INTERNAL_H
#ifdef __cplusplus
extern "C" {
#endif
#ifdef MODULE_ATMEGA_COMMON
#define ARDUINO
#endif
#define CONF_WINC_USE_SPI (1)
#define CONF_WINC_PRINTF printf
#ifndef CONF_WINC_DEBUG
#define CONF_WINC_DEBUG (0)
#endif
#ifndef M2M_LOG_LEVEL
#define M2M_LOG_LEVEL M2M_LOG_ERROR
#endif
#define NM_EDGE_INTERRUPT (1)
#ifdef __cplusplus
}
#endif
#endif /* BSP_INCLUDE_NM_BSP_INTERNAL_H */
#endif /* DOXYGEN */

View File

@ -0,0 +1,80 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_netdev
* @brief Netdev Driver for the Microchip ATWINC15x0 WiFi Module
* @{
*
* @file
* @brief Public interface for ATWINC15x0 netdev driver
*
* @author Gunar Schorcht <gunar@schorcht.net>
*/
#ifndef ATWINC15X0_H
#define ATWINC15X0_H
#include "bsp/include/nm_bsp.h"
#include "net/ethernet.h"
#include "net/netdev.h"
#include "periph/gpio.h"
#include "periph/spi.h"
#include "ringbuffer.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief ATWINC15x0 hardware and global parameters
*/
typedef struct {
spi_t spi; /**< SPI device */
spi_clk_t spi_clk; /**< SPI clock speed used */
gpio_t ssn_pin; /**< SPI SS pin (slave select LOW active) */
gpio_t reset_pin; /**< RESET_N pin (LOW active) */
gpio_t irq_pin; /**< IRQN pin (LOW active) */
gpio_t chip_en_pin; /**< CHIP_EN pin */
gpio_t wake_pin; /**< WAKE pin */
} atwinc15x0_params_t;
/**
* @brief ATWINC15x0 device descriptor type
*/
typedef struct atwinc15x0 {
netdev_t netdev; /**< Pulls in the netdev fields */
atwinc15x0_params_t params; /**< Device initialization parameters */
bool connected; /**< Indicates whether connected to an AP */
char ap[ETHERNET_ADDR_LEN]; /**< BSSID of current AP */
uint8_t channel; /**< Channel used for current AP */
int8_t rssi; /**< RSSI last measured by the WiFi module */
uint8_t* rx_buf; /**< Incoming packet in receive buffer */
uint16_t rx_len; /**< Length of an incoming packet, if there
is no packet in the buffer, it is 0 */
tpfNmBspIsr bsp_isr; /**< Board support package ISR */
bool bsp_irq_enabled; /**< Board support package interrupt enabled */
} atwinc15x0_t;
/**
* @brief Setup the ATWINC15x0 WiFi module
*
* @param[in] dev Device descriptor
* @param[in] params Parameters for device initialization
*/
void atwinc15x0_setup(atwinc15x0_t *dev, const atwinc15x0_params_t *params);
#ifdef __cplusplus
}
#endif
#endif /* ATWINC15X0_H */
/** @} */

View File

@ -107,6 +107,7 @@ PSEUDOMODULES += stdio_cdc_acm
PSEUDOMODULES += stdio_uart_rx
PSEUDOMODULES += suit_transport_%
PSEUDOMODULES += wakaama_objects_%
PSEUDOMODULES += wifi_enterprise
PSEUDOMODULES += xtimer_on_ztimer
PSEUDOMODULES += zptr
PSEUDOMODULES += ztimer%

View File

@ -0,0 +1,20 @@
PKG_NAME=driver_atwinc15x0
PKG_URL=https://github.com/arduino-libraries/WiFi101
PKG_VERSION=3301d03f82e53f60e07434a9f07ca677d992d121
PKG_LICENSE=LGPL-2.1
include $(RIOTBASE)/pkg/pkg.mk
CFLAGS += -Wno-discarded-qualifiers
CFLAGS += -Wno-empty-body
CFLAGS += -Wno-old-style-definition
CFLAGS += -Wno-unused-parameter
CFLAGS += -Wno-incompatible-pointer-types-discards-qualifiers
CFLAGS += -DETH_MODE
CFLAGS += -I$(PKG_SOURCE_DIR)/src
all:
"$(MAKE)" -C $(PKG_SOURCE_DIR)/src/driver/source -f $(RIOTBASE)/Makefile.base MODULE=driver_atwinc15x0
"$(MAKE)" -C $(PKG_SOURCE_DIR)/src/common/source -f $(RIOTBASE)/Makefile.base MODULE=driver_atwinc15x0_common
"$(MAKE)" -C $(PKG_SOURCE_DIR)/src/spi_flash/source -f $(RIOTBASE)/Makefile.base MODULE=driver_atwinc15x0_spi_flash

View File

@ -0,0 +1,6 @@
FEATURES_REQUIRED += periph_gpio_irq
FEATURES_REQUIRED += periph_spi
USEMODULE += driver_atwinc15x0
USEMODULE += driver_atwinc15x0_common
USEMODULE += driver_atwinc15x0_spi_flash

View File

@ -0,0 +1 @@
INCLUDES += -I$(PKGDIRBASE)/driver_atwinc15x0/src

View File

@ -0,0 +1,6 @@
/**
* @defgroup pkg_driver_atwinc15x0 ATWINC15x0 WiFi Module Vendor Driver Package
* @ingroup pkg
* @brief ATWINC15x0 WiFi vendor driver from the Arduino WiFi101 library
* @see https://github.com/arduino-libraries/WiFi101
*/

View File

@ -0,0 +1,71 @@
From f07d66798c27359b4348e4a4842b55f601068bd0 Mon Sep 17 00:00:00 2001
From: Gunar Schorcht <gunar@schorcht.net>
Date: Thu, 26 Mar 2020 15:26:52 +0100
Subject: [PATCH 1/6] change CONST to _CONST_
---
src/bsp/include/nm_bsp.h | 2 +-
src/driver/include/m2m_wifi.h | 4 ++--
src/driver/source/m2m_wifi.c | 4 ++--
3 files changed, 5 insertions(+), 5 deletions(-)
diff --git a/src/bsp/include/nm_bsp.h b/src/bsp/include/nm_bsp.h
index 5527bab..543d9fc 100644
--- a/src/bsp/include/nm_bsp.h
+++ b/src/bsp/include/nm_bsp.h
@@ -52,7 +52,7 @@
/*!<
* Attribute used to define memory section to map Functions in host memory.
*/
-#define CONST const
+#define _CONST_ const
/*!<
* Used for code portability.
diff --git a/src/driver/include/m2m_wifi.h b/src/driver/include/m2m_wifi.h
index 3477196..f25519a 100644
--- a/src/driver/include/m2m_wifi.h
+++ b/src/driver/include/m2m_wifi.h
@@ -1404,7 +1404,7 @@ NMI_API sint8 m2m_wifi_p2p_disconnect(void);
/**@{*/
/*!
@fn \
- NMI_API sint8 m2m_wifi_enable_ap(CONST tstrM2MAPConfig* pstrM2MAPConfig);
+ NMI_API sint8 m2m_wifi_enable_ap(_CONST_ tstrM2MAPConfig* pstrM2MAPConfig);
@param [in] pstrM2MAPConfig
A structure holding the AP configurations.
@@ -1485,7 +1485,7 @@ NMI_API sint8 m2m_wifi_p2p_disconnect(void);
@endcode
*/
-NMI_API sint8 m2m_wifi_enable_ap(CONST tstrM2MAPConfig* pstrM2MAPConfig);
+NMI_API sint8 m2m_wifi_enable_ap(_CONST_ tstrM2MAPConfig* pstrM2MAPConfig);
/**@}*/
/** @defgroup WifiDisableApFn m2m_wifi_disable_ap
* @ingroup WLANAPI
diff --git a/src/driver/source/m2m_wifi.c b/src/driver/source/m2m_wifi.c
index fc4d1eb..7b7a322 100644
--- a/src/driver/source/m2m_wifi.c
+++ b/src/driver/source/m2m_wifi.c
@@ -324,7 +324,7 @@ _EXIT0:
return ret;
}
-static sint8 m2m_validate_ap_parameters(CONST tstrM2MAPConfig* pstrM2MAPConfig)
+static sint8 m2m_validate_ap_parameters(_CONST_ tstrM2MAPConfig* pstrM2MAPConfig)
{
sint8 s8Ret = M2M_SUCCESS;
/* Check for incoming pointer */
@@ -953,7 +953,7 @@ sint8 m2m_wifi_p2p_disconnect(void)
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 m2m_wifi_enable_ap(_CONST_ tstrM2MAPConfig* pstrM2MAPConfig)
{
sint8 ret = M2M_ERR_FAIL;
if(M2M_SUCCESS == m2m_validate_ap_parameters(pstrM2MAPConfig))
--
2.17.1

View File

@ -0,0 +1,885 @@
From 6c56be47ce245340129438daafa09b4b0a45b2d2 Mon Sep 17 00:00:00 2001
From: Gunar Schorcht <gunar@schorcht.net>
Date: Thu, 26 Mar 2020 23:23:17 +0100
Subject: [PATCH 2/6] remove platform files
---
src/bsp/include/nm_bsp_arduino.h | 74 ------
src/bsp/include/nm_bsp_avr.h | 54 -----
src/bsp/include/nm_bsp_internal.h | 59 -----
src/bsp/include/nm_bsp_samd21.h | 52 -----
src/bsp/source/nm_bsp_arduino.c | 214 ------------------
src/bsp/source/nm_bsp_arduino_avr.c | 164 --------------
.../source/nm_bus_wrapper_samd21.cpp | 200 ----------------
7 files changed, 817 deletions(-)
delete mode 100644 src/bsp/include/nm_bsp_arduino.h
delete mode 100644 src/bsp/include/nm_bsp_avr.h
delete mode 100644 src/bsp/include/nm_bsp_internal.h
delete mode 100644 src/bsp/include/nm_bsp_samd21.h
delete mode 100644 src/bsp/source/nm_bsp_arduino.c
delete mode 100644 src/bsp/source/nm_bsp_arduino_avr.c
delete mode 100644 src/bus_wrapper/source/nm_bus_wrapper_samd21.cpp
diff --git a/src/bsp/include/nm_bsp_arduino.h b/src/bsp/include/nm_bsp_arduino.h
deleted file mode 100644
index 77417e8..0000000
--- a/src/bsp/include/nm_bsp_arduino.h
+++ /dev/null
@@ -1,74 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains NMC1500 BSP APIs definitions.
- *
- * 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
- *
- */
-
-#ifndef _NM_BSP_ARDUINO_H_
-#define _NM_BSP_ARDUINO_H_
-
-#include <stdint.h>
-
-#include <Arduino.h>
-
-/*
- * Arduino variants may redefine those pins.
- * If no pins are specified the following defaults are used:
- * WINC1501_RESET_PIN - pin 5
- * WINC1501_INTN_PIN - pin 7
- * WINC1501_CHIP_EN_PIN - not connected (tied to VCC)
- */
-#if !defined(WINC1501_RESET_PIN)
- #define WINC1501_RESET_PIN 5
-#endif
-#if !defined(WINC1501_INTN_PIN)
- #define WINC1501_INTN_PIN 7
-#endif
-#if !defined(WINC1501_SPI_CS_PIN)
- #define WINC1501_SPI_CS_PIN 10
-#endif
-#if !defined(WINC1501_CHIP_EN_PIN)
- #define WINC1501_CHIP_EN_PIN -1
-#endif
-
-extern int8_t gi8Winc1501CsPin;
-extern int8_t gi8Winc1501ResetPin;
-extern int8_t gi8Winc1501IntnPin;
-extern int8_t gi8Winc1501ChipEnPin;
-
-#endif /* _NM_BSP_ARDUINO_H_ */
diff --git a/src/bsp/include/nm_bsp_avr.h b/src/bsp/include/nm_bsp_avr.h
deleted file mode 100644
index c5991f2..0000000
--- a/src/bsp/include/nm_bsp_avr.h
+++ /dev/null
@@ -1,54 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains NMC1500 BSP APIs definitions.
- *
- * 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
- *
- */
-
-#ifndef _NM_BSP_AVR_H_
-#define _NM_BSP_AVR_H_
-
-#pragma once
-
-#define NM_DEBUG 0
-#define NM_BSP_PRINTF
-
-#define CONF_WINC_USE_SPI 1
-
-#define NM_EDGE_INTERRUPT 1
-
-#endif /* _NM_BSP_AVR_H_ */
diff --git a/src/bsp/include/nm_bsp_internal.h b/src/bsp/include/nm_bsp_internal.h
deleted file mode 100644
index 5117a1d..0000000
--- a/src/bsp/include/nm_bsp_internal.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains NMC1500 BSP APIs declarations.
- *
- * 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
- *
- */
-/**@defgroup BSPDefine Defines
- * @ingroup nm_bsp
- * @{
- */
-#ifndef _NM_BSP_INTERNAL_H_
-#define _NM_BSP_INTERNAL_H_
-
-#ifdef ARDUINO_ARCH_AVR
-#define LIMITED_RAM_DEVICE
-#include "bsp/include/nm_bsp_avr.h"
-#else
-#include "bsp/include/nm_bsp_samd21.h"
-#endif
-
-#if defined(ARDUINO) && !defined(ARDUINO_SAMD_MKR1000)
-#define CONF_PERIPH
-#endif
-
-#endif //_NM_BSP_INTERNAL_H_
\ No newline at end of file
diff --git a/src/bsp/include/nm_bsp_samd21.h b/src/bsp/include/nm_bsp_samd21.h
deleted file mode 100644
index 296cd20..0000000
--- a/src/bsp/include/nm_bsp_samd21.h
+++ /dev/null
@@ -1,52 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains NMC1500 BSP APIs definitions.
- *
- * 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
- *
- */
-
-#ifndef _NM_BSP_SAMD21_H_
-#define _NM_BSP_SAMD21_H_
-
-#define NM_DEBUG 0
-#define NM_BSP_PRINTF
-
-#define CONF_WINC_USE_SPI 1
-
-#define NM_EDGE_INTERRUPT 1
-
-#endif /* _NM_BSP_SAMD21_H_ */
diff --git a/src/bsp/source/nm_bsp_arduino.c b/src/bsp/source/nm_bsp_arduino.c
deleted file mode 100644
index b10674b..0000000
--- a/src/bsp/source/nm_bsp_arduino.c
+++ /dev/null
@@ -1,214 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains SAMD21 BSP APIs implementation.
- *
- * Copyright (c) 2014 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.
- *
- * 4. This software may only be redistributed and used in connection with an
- * Atmel microcontroller product.
- *
- * 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 "bsp/include/nm_bsp.h"
-#include "bsp/include/nm_bsp_arduino.h"
-#include "common/include/nm_common.h"
-
-int8_t gi8Winc1501CsPin = WINC1501_SPI_CS_PIN;
-int8_t gi8Winc1501ResetPin = WINC1501_RESET_PIN;
-int8_t gi8Winc1501IntnPin = WINC1501_INTN_PIN;
-int8_t gi8Winc1501ChipEnPin = WINC1501_CHIP_EN_PIN;
-
-static tpfNmBspIsr gpfIsr;
-
-void __attribute__((weak)) attachInterruptMultiArch(uint32_t pin, void *chip_isr, uint32_t mode)
-{
- attachInterrupt(pin, chip_isr, mode);
-}
-
-void __attribute__((weak)) detachInterruptMultiArch(uint32_t pin)
-{
- detachInterrupt(pin);
-}
-
-static void chip_isr(void)
-{
- if (gpfIsr) {
- gpfIsr();
- }
-}
-
-/*
- * @fn init_chip_pins
- * @brief Initialize reset, chip enable and wake pin
- * @author M.S.M
- * @date 11 July 2012
- * @version 1.0
- */
-static void init_chip_pins(void)
-{
- if (gi8Winc1501ResetPin > -1)
- {
- /* Configure RESETN pin as output. */
- pinMode(gi8Winc1501ResetPin, OUTPUT);
- digitalWrite(gi8Winc1501ResetPin, HIGH);
- }
-
- /* Configure INTN pins as input. */
- pinMode(gi8Winc1501IntnPin, INPUT);
-
- if (gi8Winc1501ChipEnPin > -1)
- {
- /* Configure CHIP_EN as pull-up */
- pinMode(gi8Winc1501ChipEnPin, INPUT_PULLUP);
- }
-}
-
-static void deinit_chip_pins(void)
-{
- if (gi8Winc1501ResetPin > -1)
- {
- digitalWrite(gi8Winc1501ResetPin, LOW);
- pinMode(gi8Winc1501ResetPin, INPUT);
- }
-
- if (gi8Winc1501ChipEnPin > -1)
- {
- pinMode(gi8Winc1501ChipEnPin, INPUT);
- }
-}
-
-/*
- * @fn nm_bsp_init
- * @brief Initialize BSP
- * @return 0 in case of success and -1 in case of failure
- * @author M.S.M
- * @date 11 July 2012
- * @version 1.0
- */
-sint8 nm_bsp_init(void)
-{
- gpfIsr = NULL;
-
- init_chip_pins();
-
- nm_bsp_reset();
-
- return M2M_SUCCESS;
-}
-
-/**
- * @fn nm_bsp_deinit
- * @brief De-iInitialize BSP
- * @return 0 in case of success and -1 in case of failure
- * @author M. Abdelmawla
- * @date 11 July 2012
- * @version 1.0
- */
-sint8 nm_bsp_deinit(void)
-{
- deinit_chip_pins();
-
- return M2M_SUCCESS;
-}
-
-/**
- * @fn nm_bsp_reset
- * @brief Reset NMC1500 SoC by setting CHIP_EN and RESET_N signals low,
- * CHIP_EN high then RESET_N high
- * @author M. Abdelmawla
- * @date 11 July 2012
- * @version 1.0
- */
-void nm_bsp_reset(void)
-{
- if (gi8Winc1501ResetPin > -1)
- {
- digitalWrite(gi8Winc1501ResetPin, LOW);
- nm_bsp_sleep(100);
- digitalWrite(gi8Winc1501ResetPin, HIGH);
- nm_bsp_sleep(100);
- }
-}
-
-/*
- * @fn nm_bsp_sleep
- * @brief Sleep in units of mSec
- * @param[IN] u32TimeMsec
- * Time in milliseconds
- * @author M.S.M
- * @date 28 OCT 2013
- * @version 1.0
- */
-void nm_bsp_sleep(uint32 u32TimeMsec)
-{
- while (u32TimeMsec--) {
- delay(1);
- }
-}
-
-/*
- * @fn nm_bsp_register_isr
- * @brief Register interrupt service routine
- * @param[IN] pfIsr
- * Pointer to ISR handler
- * @author M.S.M
- * @date 28 OCT 2013
- * @sa tpfNmBspIsr
- * @version 1.0
- */
-void nm_bsp_register_isr(tpfNmBspIsr pfIsr)
-{
- gpfIsr = pfIsr;
- attachInterruptMultiArch(gi8Winc1501IntnPin, chip_isr, FALLING);
-}
-
-/*
- * @fn nm_bsp_interrupt_ctrl
- * @brief Enable/Disable interrupts
- * @param[IN] u8Enable
- * '0' disable interrupts. '1' enable interrupts
- * @author M.S.M
- * @date 28 OCT 2013
- * @version 1.0
- */
-void nm_bsp_interrupt_ctrl(uint8 u8Enable)
-{
- if (u8Enable) {
- attachInterruptMultiArch(gi8Winc1501IntnPin, chip_isr, FALLING);
- } else {
- detachInterruptMultiArch(gi8Winc1501IntnPin);
- }
-}
diff --git a/src/bsp/source/nm_bsp_arduino_avr.c b/src/bsp/source/nm_bsp_arduino_avr.c
deleted file mode 100644
index 050d5d5..0000000
--- a/src/bsp/source/nm_bsp_arduino_avr.c
+++ /dev/null
@@ -1,164 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains SAMD21 BSP APIs implementation.
- *
- * Copyright (c) 2014 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.
- *
- * 4. This software may only be redistributed and used in connection with an
- * Atmel microcontroller product.
- *
- * 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 ARDUINO_ARCH_AVR
-
-#include "bsp/include/nm_bsp.h"
-#include "bsp/include/nm_bsp_arduino.h"
-#include "common/include/nm_common.h"
-
-#define IS_MEGA (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560))
-
-static tpfNmBspIsr gpfIsr;
-
-volatile uint8_t *_receivePortRegister;
-volatile uint8_t *_pcint_maskreg;
-uint8_t _receiveBitMask;
-volatile uint8_t prev_pin_read = 1;
-
-uint8_t rx_pin_read()
-{
- return *_receivePortRegister & _receiveBitMask;
-}
-
-#if !IS_MEGA
-
-#if defined(PCINT0_vect)
-ISR(PCINT0_vect)
-{
- if (!rx_pin_read() && gpfIsr)
- {
- gpfIsr();
- }
-}
-#endif
-
-#if defined(PCINT1_vect)
-ISR(PCINT1_vect, ISR_ALIASOF(PCINT0_vect));
-#endif
-
-#if defined(PCINT2_vect)
-ISR(PCINT2_vect, ISR_ALIASOF(PCINT0_vect));
-#endif
-
-#if defined(PCINT3_vect)
-ISR(PCINT3_vect, ISR_ALIASOF(PCINT0_vect));
-#endif
-
-#endif // !IS_MEGA
-
-#if defined(TIMER4_OVF_vect)
-ISR(TIMER4_OVF_vect) {
- uint8_t curr_pin_read = rx_pin_read();
- if ((curr_pin_read != prev_pin_read) && !curr_pin_read && gpfIsr)
- {
- gpfIsr();
- }
- prev_pin_read = curr_pin_read;
-}
-
-// stategy 3 - start a timer and perform a sort of polling
-void attachFakeInterruptToTimer(void) {
- TCCR4B = (1<<CS41);
- TIMSK4 = (1<<TOIE4);
- OCR4C = 0xFF;
-}
-#else
-void attachFakeInterruptToTimer(void) {
-}
-#endif
-
-// strategy 1 - attach external interrupt to change pin (works on 328)
-void attachInterruptToChangePin(int pin) {
- pinMode(pin, INPUT_PULLUP);
- _receiveBitMask = digitalPinToBitMask(pin);
- uint8_t port = digitalPinToPort(pin);
- _receivePortRegister = portInputRegister(port);
-
- if (!digitalPinToPCICR(pin)) {
- //need to fallback to strategy 2
- attachFakeInterruptToTimer();
- return;
- }
-
- *digitalPinToPCICR(pin) |= _BV(digitalPinToPCICRbit(pin));
- _pcint_maskreg = digitalPinToPCMSK(pin);
- *_pcint_maskreg |= _BV(digitalPinToPCMSKbit(pin));
-}
-
-void detachInterruptToChangePin(int pin) {
- *_pcint_maskreg &= ~(_BV(digitalPinToPCMSKbit(pin)));
-}
-
-void attachInterruptMultiArch(uint32_t pin, void *chip_isr, uint32_t mode)
-{
- int pin_irq;
- gpfIsr = chip_isr;
-
- // stategy 0 - attach external interrupt to pin (works on 32u4)
- pin_irq = digitalPinToInterrupt((int)pin);
- if (pin_irq == (int)NOT_AN_INTERRUPT) {
- attachInterruptToChangePin(pin);
- return;
- }
-
- attachInterrupt(pin_irq, chip_isr, mode);
- return;
-}
-
-void detachInterruptMultiArch(uint32_t pin)
-{
- int pin_irq;
-
- pin_irq = digitalPinToInterrupt((int)pin);
- if (pin_irq == (int)NOT_AN_INTERRUPT) {
- detachInterruptToChangePin(pin);
- return;
- }
-
- detachInterrupt(pin_irq);
-}
-
-#endif
-
diff --git a/src/bus_wrapper/source/nm_bus_wrapper_samd21.cpp b/src/bus_wrapper/source/nm_bus_wrapper_samd21.cpp
deleted file mode 100644
index 22a7473..0000000
--- a/src/bus_wrapper/source/nm_bus_wrapper_samd21.cpp
+++ /dev/null
@@ -1,200 +0,0 @@
-/**
- *
- * \file
- *
- * \brief This module contains NMC1000 bus wrapper APIs implementation.
- *
- * Copyright (c) 2014 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.
- *
- * 4. This software may only be redistributed and used in connection with an
- * Atmel microcontroller product.
- *
- * 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 <Arduino.h>
-#include <SPI.h>
-
-/*
- * Variants may define an alternative SPI instace to use for WiFi101.
- * If not defined the following defaults are used:
- * WINC1501_SPI - SPI
- */
-#if !defined(WINC1501_SPI)
- #define WINC1501_SPI SPI
-#endif
-
-extern "C" {
-
-#include "bsp/include/nm_bsp.h"
-#include "bsp/include/nm_bsp_arduino.h"
-#include "common/include/nm_common.h"
-#include "bus_wrapper/include/nm_bus_wrapper.h"
-
-}
-
-#define NM_BUS_MAX_TRX_SZ 256
-
-tstrNmBusCapabilities egstrNmBusCapabilities =
-{
- NM_BUS_MAX_TRX_SZ
-};
-
-static const SPISettings wifi_SPISettings(12000000L, MSBFIRST, SPI_MODE0);
-
-static sint8 spi_rw(uint8* pu8Mosi, uint8* pu8Miso, uint16 u16Sz)
-{
- uint8 u8Dummy = 0;
- uint8 u8SkipMosi = 0, u8SkipMiso = 0;
-
- if (!pu8Mosi) {
- pu8Mosi = &u8Dummy;
- u8SkipMosi = 1;
- }
- else if(!pu8Miso) {
- pu8Miso = &u8Dummy;
- u8SkipMiso = 1;
- }
- else {
- return M2M_ERR_BUS_FAIL;
- }
-
- WINC1501_SPI.beginTransaction(wifi_SPISettings);
- digitalWrite(gi8Winc1501CsPin, LOW);
-
- while (u16Sz) {
- *pu8Miso = WINC1501_SPI.transfer(*pu8Mosi);
-
- u16Sz--;
- if (!u8SkipMiso)
- pu8Miso++;
- if (!u8SkipMosi)
- pu8Mosi++;
- }
-
- digitalWrite(gi8Winc1501CsPin, HIGH);
- WINC1501_SPI.endTransaction();
-
- return M2M_SUCCESS;
-}
-
-extern "C" {
-
-/*
-* @fn nm_bus_init
-* @brief Initialize the bus wrapper
-* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure
-* @author M.S.M
-* @date 28 oct 2013
-* @version 1.0
-*/
-sint8 nm_bus_init(void * /* pvInitValue */)
-{
- sint8 result = M2M_SUCCESS;
-
- /* Configure SPI peripheral. */
- WINC1501_SPI.begin();
-
- /* Configure CS PIN. */
- pinMode(gi8Winc1501CsPin, OUTPUT);
- digitalWrite(gi8Winc1501CsPin, HIGH);
-
- /* Reset WINC1500. */
- nm_bsp_reset();
- nm_bsp_sleep(1);
-
- return result;
-}
-
-/*
-* @fn nm_bus_ioctl
-* @brief send/receive from the bus
-* @param[IN] u8Cmd
-* IOCTL command for the operation
-* @param[IN] pvParameter
-* Arbitrary parameter depenging on IOCTL
-* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure
-* @author M.S.M
-* @date 28 oct 2013
-* @note For SPI only, it's important to be able to send/receive at the same time
-* @version 1.0
-*/
-sint8 nm_bus_ioctl(uint8 u8Cmd, void* pvParameter)
-{
- sint8 s8Ret = 0;
- switch(u8Cmd)
- {
- case NM_BUS_IOCTL_RW: {
- tstrNmSpiRw *pstrParam = (tstrNmSpiRw *)pvParameter;
- s8Ret = spi_rw(pstrParam->pu8InBuf, pstrParam->pu8OutBuf, pstrParam->u16Sz);
- }
- break;
- default:
- s8Ret = -1;
- M2M_ERR("invalide ioclt cmd\n");
- break;
- }
-
- return s8Ret;
-}
-
-/*
-* @fn nm_bus_deinit
-* @brief De-initialize the bus wrapper
-* @author M.S.M
-* @date 28 oct 2013
-* @version 1.0
-*/
-sint8 nm_bus_deinit(void)
-{
- WINC1501_SPI.end();
- return 0;
-}
-
-/*
-* @fn nm_bus_reinit
-* @brief re-initialize the bus wrapper
-* @param [in] void *config
-* re-init configuration data
-* @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure
-* @author Dina El Sissy
-* @date 19 Sept 2012
-* @version 1.0
-*/
-sint8 nm_bus_reinit(void* /* config */)
-{
- return M2M_SUCCESS;
-}
-
-} // extern "C"
-
--
2.17.1

View File

@ -0,0 +1,40 @@
From f18b91094401e75f4700d272c1072a92ac870beb Mon Sep 17 00:00:00 2001
From: Gunar Schorcht <gunar@schorcht.net>
Date: Thu, 26 Mar 2020 23:55:39 +0100
Subject: [PATCH 3/6] change default debug config
---
src/common/include/nm_debug.h | 6 ++++++
1 file changed, 6 insertions(+)
diff --git a/src/common/include/nm_debug.h b/src/common/include/nm_debug.h
index a710f6c..50137cf 100644
--- a/src/common/include/nm_debug.h
+++ b/src/common/include/nm_debug.h
@@ -42,6 +42,8 @@
#ifndef _NM_DEBUG_H_
#define _NM_DEBUG_H_
+#include <stdio.h>
+
#include "bsp/include/nm_bsp.h"
#include "bsp/include/nm_bsp_internal.h"
@@ -58,10 +60,14 @@
#define M2M_LOG_DBG 4
#if (defined __APS3_CORTUS__)
+#ifndef M2M_LOG_LEVEL
#define M2M_LOG_LEVEL M2M_LOG_INFO
+#endif
#else
+#ifndef M2M_LOG_LEVEL
#define M2M_LOG_LEVEL M2M_LOG_REQ
#endif
+#endif
#define M2M_ERR(...)
--
2.17.1

View File

@ -0,0 +1,25 @@
From fc93442983afdc95f28a777429279ad5e4fb7fd7 Mon Sep 17 00:00:00 2001
From: Gunar Schorcht <gunar@schorcht.net>
Date: Fri, 27 Mar 2020 13:22:22 +0100
Subject: [PATCH 4/6] fix ETH_MODE compilation problem
---
src/driver/source/m2m_wifi.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/driver/source/m2m_wifi.c b/src/driver/source/m2m_wifi.c
index 7b7a322..0256960 100644
--- a/src/driver/source/m2m_wifi.c
+++ b/src/driver/source/m2m_wifi.c
@@ -242,7 +242,7 @@ static void m2m_wifi_cb(uint8 u8OpCode, uint16 u16DataSize, uint32 u32Addr)
{
uint8 u8SetRxDone;
tstrM2mIpRsvdPkt strM2mRsvd;
- if(hif_receive(u32Addr, &strM2mRsvd ,sizeof(tstrM2mIpRsvdPkt), 0) == M2M_SUCCESS)
+ if(hif_receive(u32Addr, (uint8*)&strM2mRsvd ,sizeof(tstrM2mIpRsvdPkt), 0) == M2M_SUCCESS)
{
tstrM2mIpCtrlBuf strM2mIpCtrlBuf;
uint16 u16Offset = strM2mRsvd.u16PktOffset;
--
2.17.1

View File

@ -0,0 +1,25 @@
From 0e118023ed9a1426e5299b9e6802e11bd488de8b Mon Sep 17 00:00:00 2001
From: Gunar Schorcht <gunar@schorcht.net>
Date: Mon, 30 Mar 2020 02:22:18 +0200
Subject: [PATCH 5/6] remove dependency from spi_flash module
---
src/driver/source/nmdrv.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/driver/source/nmdrv.c b/src/driver/source/nmdrv.c
index 396ade9..3de10c3 100644
--- a/src/driver/source/nmdrv.c
+++ b/src/driver/source/nmdrv.c
@@ -385,7 +385,7 @@ sint8 nm_drv_deinit(void * arg)
}
/* Disable SPI flash to save power when the chip is off */
- ret = spi_flash_enable(0);
+ /* ret = spi_flash_enable(0); */
if (M2M_SUCCESS != ret) {
M2M_ERR("[nmi stop]: SPI flash disable fail\n");
goto ERR1;
--
2.17.1

View File

@ -0,0 +1,374 @@
From f904e4d6ec1d6d5afa8f7b6da2822fb9e332796a Mon Sep 17 00:00:00 2001
From: Gunar Schorcht <gunar@schorcht.net>
Date: Thu, 2 Apr 2020 01:54:57 +0200
Subject: [PATCH 6/6] rename spi_flash_* functons
---
src/driver/source/nmdrv.c | 2 +-
src/spi_flash/include/spi_flash.h | 10 ++--
src/spi_flash/source/spi_flash.c | 86 +++++++++++++++----------------
3 files changed, 49 insertions(+), 49 deletions(-)
diff --git a/src/driver/source/nmdrv.c b/src/driver/source/nmdrv.c
index 3de10c3..d29560a 100644
--- a/src/driver/source/nmdrv.c
+++ b/src/driver/source/nmdrv.c
@@ -385,7 +385,7 @@ sint8 nm_drv_deinit(void * arg)
}
/* Disable SPI flash to save power when the chip is off */
- /* ret = spi_flash_enable(0); */
+ ret = atwinc15x0_flash_enable(0);
if (M2M_SUCCESS != ret) {
M2M_ERR("[nmi stop]: SPI flash disable fail\n");
goto ERR1;
diff --git a/src/spi_flash/include/spi_flash.h b/src/spi_flash/include/spi_flash.h
index a85aa72..41515d8 100644
--- a/src/spi_flash/include/spi_flash.h
+++ b/src/spi_flash/include/spi_flash.h
@@ -124,7 +124,7 @@ extern "C" {
* @brief Enable spi flash operations
* @version 1.0
*/
-sint8 spi_flash_enable(uint8 enable);
+sint8 atwinc15x0_flash_enable(uint8 enable);
/** \defgroup SPIFLASHAPI Function
* @ingroup SPIFLASH
*/
@@ -139,7 +139,7 @@ sint8 spi_flash_enable(uint8 enable);
* @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);
+uint32 atwinc15x0_flash_get_size(void);
/**@}*/
/** @defgroup SPiFlashRead spi_flash_read
@@ -166,7 +166,7 @@ uint32 spi_flash_get_size(void);
* @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);
+sint8 atwinc15x0_flash_read(uint8 *pu8Buf, uint32 u32Addr, uint32 u32Sz);
/**@}*/
/** @defgroup SPiFlashWrite spi_flash_write
@@ -197,7 +197,7 @@ sint8 spi_flash_read(uint8 *pu8Buf, uint32 u32Addr, uint32 u32Sz);
* @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);
+sint8 atwinc15x0_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz);
/**@}*/
/** @defgroup SPiFlashErase spi_flash_erase
@@ -223,7 +223,7 @@ sint8 spi_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz);
* @return The function returns @ref M2M_SUCCESS for successful operations and a negative value otherwise.
*/
-sint8 spi_flash_erase(uint32 u32Offset, uint32 u32Sz);
+sint8 atwinc15x0_flash_erase(uint32 u32Offset, uint32 u32Sz);
/**@}*/
#ifdef ARDUINO
#ifdef __cplusplus
diff --git a/src/spi_flash/source/spi_flash.c b/src/spi_flash/source/spi_flash.c
index 12eff59..e70827c 100644
--- a/src/spi_flash/source/spi_flash.c
+++ b/src/spi_flash/source/spi_flash.c
@@ -96,7 +96,7 @@ SPI Flash DMA
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_read_status_reg(uint8 * val)
+static sint8 atwinc15x0_flash_read_status_reg(uint8 * val)
{
sint8 ret = M2M_SUCCESS;
uint8 cmd[1];
@@ -130,7 +130,7 @@ static sint8 spi_flash_read_status_reg(uint8 * val)
* @author M. Abdelmawla
* @version 1.0
*/
-static uint8 spi_flash_read_security_reg(void)
+static uint8 atwinc15x0_flash_read_security_reg(void)
{
uint8 cmd[1];
uint32 reg;
@@ -161,7 +161,7 @@ static uint8 spi_flash_read_security_reg(void)
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_gang_unblock(void)
+static sint8 atwinc15x0_flash_gang_unblock(void)
{
uint8 cmd[1];
uint32 val = 0;
@@ -191,7 +191,7 @@ static sint8 spi_flash_gang_unblock(void)
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_clear_security_flags(void)
+static sint8 atwinc15x0_flash_clear_security_flags(void)
{
uint8 cmd[1];
uint32 val = 0;
@@ -229,7 +229,7 @@ static sint8 spi_flash_clear_security_flags(void)
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_load_to_cortus_mem(uint32 u32MemAdr, uint32 u32FlashAdr, uint32 u32Sz)
+static sint8 atwinc15x0_flash_load_to_cortus_mem(uint32 u32MemAdr, uint32 u32FlashAdr, uint32 u32Sz)
{
uint8 cmd[5];
uint32 val = 0;
@@ -271,7 +271,7 @@ static sint8 spi_flash_load_to_cortus_mem(uint32 u32MemAdr, uint32 u32FlashAdr,
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_sector_erase(uint32 u32FlashAdr)
+static sint8 atwinc15x0_flash_sector_erase(uint32 u32FlashAdr)
{
uint8 cmd[4];
uint32 val = 0;
@@ -309,7 +309,7 @@ static sint8 spi_flash_sector_erase(uint32 u32FlashAdr)
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_write_enable(void)
+static sint8 atwinc15x0_flash_write_enable(void)
{
uint8 cmd[1];
uint32 val = 0;
@@ -339,7 +339,7 @@ static sint8 spi_flash_write_enable(void)
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_write_disable(void)
+static sint8 atwinc15x0_flash_write_disable(void)
{
uint8 cmd[1];
uint32 val = 0;
@@ -374,7 +374,7 @@ static sint8 spi_flash_write_disable(void)
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_page_program(uint32 u32MemAdr, uint32 u32FlashAdr, uint32 u32Sz)
+static sint8 atwinc15x0_flash_page_program(uint32 u32MemAdr, uint32 u32FlashAdr, uint32 u32Sz)
{
uint8 cmd[4];
uint32 val = 0;
@@ -417,11 +417,11 @@ static sint8 spi_flash_page_program(uint32 u32MemAdr, uint32 u32FlashAdr, uint32
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_read_internal(uint8 *pu8Buf, uint32 u32Addr, uint32 u32Sz)
+static sint8 atwinc15x0_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);
+ ret = atwinc15x0_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:
@@ -441,21 +441,21 @@ ERR:
* @author M. Abdelmawla
* @version 1.0
*/
-static sint8 spi_flash_pp(uint32 u32Offset, uint8 *pu8Buf, uint16 u16Sz)
+static sint8 atwinc15x0_flash_pp(uint32 u32Offset, uint8 *pu8Buf, uint16 u16Sz)
{
sint8 ret = M2M_SUCCESS;
uint8 tmp;
- spi_flash_write_enable();
+ atwinc15x0_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);
+ ret += atwinc15x0_flash_page_program(HOST_SHARE_MEM_BASE, u32Offset, u16Sz);
+ ret += atwinc15x0_flash_read_status_reg(&tmp);
do
{
if(ret != M2M_SUCCESS) goto ERR;
- ret += spi_flash_read_status_reg(&tmp);
+ ret += atwinc15x0_flash_read_status_reg(&tmp);
}while(tmp & 0x01);
- ret += spi_flash_write_disable();
+ ret += atwinc15x0_flash_write_disable();
ERR:
return ret;
}
@@ -467,7 +467,7 @@ ERR:
* @author M.S.M
* @version 1.0
*/
-static uint32 spi_flash_rdid(void)
+static uint32 atwinc15x0_flash_rdid(void)
{
unsigned char cmd[1];
uint32 reg = 0;
@@ -504,19 +504,19 @@ static uint32 spi_flash_rdid(void)
* @version 1.0
*/
#if 0
-static void spi_flash_unlock(void)
+static void atwinc15x0_flash_unlock(void)
{
uint8 tmp;
- tmp = spi_flash_read_security_reg();
- spi_flash_clear_security_flags();
+ tmp = atwinc15x0_flash_read_security_reg();
+ atwinc15x0_flash_clear_security_flags();
if(tmp & 0x80)
{
- spi_flash_write_enable();
- spi_flash_gang_unblock();
+ atwinc15x0_flash_write_enable();
+ atwinc15x0_flash_gang_unblock();
}
}
#endif
-static void spi_flash_enter_low_power_mode(void) {
+static void atwinc15x0_flash_enter_low_power_mode(void) {
volatile unsigned long tmp;
unsigned char* cmd = (unsigned char*) &tmp;
@@ -531,7 +531,7 @@ static void spi_flash_enter_low_power_mode(void) {
}
-static void spi_flash_leave_low_power_mode(void) {
+static void atwinc15x0_flash_leave_low_power_mode(void) {
volatile unsigned long tmp;
unsigned char* cmd = (unsigned char*) &tmp;
@@ -553,7 +553,7 @@ static void spi_flash_leave_low_power_mode(void) {
* @author M. Abdelmawla
* @version 1.0
*/
-sint8 spi_flash_enable(uint8 enable)
+sint8 atwinc15x0_flash_enable(uint8 enable)
{
sint8 s8Ret = M2M_SUCCESS;
if(REV(nmi_get_chipid()) >= REV_3A0) {
@@ -569,9 +569,9 @@ sint8 spi_flash_enable(uint8 enable)
u32Val |= ((0x1111ul) << 12);
nm_write_reg(0x1410, u32Val);
if(enable) {
- spi_flash_leave_low_power_mode();
+ atwinc15x0_flash_leave_low_power_mode();
} else {
- spi_flash_enter_low_power_mode();
+ atwinc15x0_flash_enter_low_power_mode();
}
/* Disable pinmux to SPI flash to minimize leakage. */
u32Val &= ~((0x7777ul) << 12);
@@ -595,14 +595,14 @@ ERR1:
* @author M. Abdelmawla
* @version 1.0
*/
-sint8 spi_flash_read(uint8 *pu8Buf, uint32 u32offset, uint32 u32Sz)
+sint8 atwinc15x0_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);
+ ret = atwinc15x0_flash_read_internal(pu8Buf, u32offset, FLASH_BLOCK_SIZE);
if(M2M_SUCCESS != ret) goto ERR;
u32Sz -= FLASH_BLOCK_SIZE;
u32offset += FLASH_BLOCK_SIZE;
@@ -610,7 +610,7 @@ sint8 spi_flash_read(uint8 *pu8Buf, uint32 u32offset, uint32 u32Sz)
} while(u32Sz > FLASH_BLOCK_SIZE);
}
- ret = spi_flash_read_internal(pu8Buf, u32offset, u32Sz);
+ ret = atwinc15x0_flash_read_internal(pu8Buf, u32offset, u32Sz);
ERR:
return ret;
@@ -629,7 +629,7 @@ ERR:
* @author M. Abdelmawla
* @version 1.0
*/
-sint8 spi_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz)
+sint8 atwinc15x0_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz)
{
#ifdef PROFILING
uint32 t1 = 0;
@@ -657,7 +657,7 @@ sint8 spi_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz)
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)
+ if(atwinc15x0_flash_pp(u32Offset, pu8Buf, (uint16)BSP_MIN(u32Sz, u32wsz))!=M2M_SUCCESS)
{
ret = M2M_ERR_FAIL;
goto ERR;
@@ -672,7 +672,7 @@ sint8 spi_flash_write(uint8* pu8Buf, uint32 u32Offset, uint32 u32Sz)
u32wsz = BSP_MIN(u32Sz, u32Blksz);
/*write complete page or the remaining data*/
- if(spi_flash_pp(u32Offset, pu8Buf, (uint16)u32wsz)!=M2M_SUCCESS)
+ if(atwinc15x0_flash_pp(u32Offset, pu8Buf, (uint16)u32wsz)!=M2M_SUCCESS)
{
ret = M2M_ERR_FAIL;
goto ERR;
@@ -706,7 +706,7 @@ ERR:
* @author M. Abdelmawla
* @version 1.0
*/
-sint8 spi_flash_erase(uint32 u32Offset, uint32 u32Sz)
+sint8 atwinc15x0_flash_erase(uint32 u32Offset, uint32 u32Sz)
{
uint32 i = 0;
sint8 ret = M2M_SUCCESS;
@@ -718,14 +718,14 @@ sint8 spi_flash_erase(uint32 u32Offset, uint32 u32Sz)
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);
+ ret += atwinc15x0_flash_write_enable();
+ ret += atwinc15x0_flash_read_status_reg(&tmp);
+ ret += atwinc15x0_flash_sector_erase(i + 10);
+ ret += atwinc15x0_flash_read_status_reg(&tmp);
do
{
if(ret != M2M_SUCCESS) goto ERR;
- ret += spi_flash_read_status_reg(&tmp);
+ ret += atwinc15x0_flash_read_status_reg(&tmp);
}while(tmp & 0x01);
}
@@ -744,14 +744,14 @@ ERR:
* @author M.S.M
* @version 1.0
*/
-uint32 spi_flash_get_size(void)
+uint32 atwinc15x0_flash_get_size(void)
{
uint32 u32FlashId = 0, u32FlashPwr = 0;
static uint32 gu32InernalFlashSize= 0;
if(!gu32InernalFlashSize)
{
- u32FlashId = spi_flash_rdid();//spi_flash_probe();
+ u32FlashId = atwinc15x0_flash_rdid();//spi_flash_probe();
if(u32FlashId != 0xffffffff)
{
/*flash size is the third byte from the FLASH RDID*/
@@ -767,4 +767,4 @@ uint32 spi_flash_get_size(void)
}
return gu32InernalFlashSize;
-}
\ No newline at end of file
+}
--
2.17.1

View File

@ -33,6 +33,11 @@
#include "at86rf2xx_params.h"
#endif
#ifdef MODULE_ATWINC15X0
#include "atwinc15x0.h"
#include "atwinc15x0_params.h"
#endif
#ifdef MODULE_ENC28J60
#include "enc28j60.h"
#include "enc28j60_params.h"
@ -77,6 +82,10 @@
#define LWIP_NETIF_NUMOF ARRAY_SIZE(at86rf2xx_params)
#endif
#ifdef MODULE_ATWINC15X0 /* is mutual exclusive with above ifdef */
#define LWIP_NETIF_NUMOF ARRAY_SIZE(atwinc15x0_params)
#endif
#ifdef MODULE_ENC28J60 /* is mutual exclusive with above ifdef */
#define LWIP_NETIF_NUMOF ARRAY_SIZE(enc28j60_params)
#endif
@ -117,6 +126,10 @@ static netdev_tap_t netdev_taps[LWIP_NETIF_NUMOF];
static at86rf2xx_t at86rf2xx_devs[LWIP_NETIF_NUMOF];
#endif
#ifdef MODULE_ATWINC15X0
static atwinc15x0_t atwinc15x0_devs[LWIP_NETIF_NUMOF];
#endif
#ifdef MODULE_ENC28J60
static enc28j60_t enc28j60_devs[LWIP_NETIF_NUMOF];
#endif
@ -194,6 +207,23 @@ void lwip_bootstrap(void)
return;
}
}
#elif defined(MODULE_ATWINC15X0)
for (unsigned i = 0; i < LWIP_NETIF_NUMOF; i++) {
atwinc15x0_setup(&atwinc15x0_devs[i], &atwinc15x0_params[i]);
#ifdef MODULE_LWIP_IPV4
if (netif_add(&netif[0], IP4_ADDR_ANY, IP4_ADDR_ANY, IP4_ADDR_ANY,
&atwinc15x0_devs[i], lwip_netdev_init, tcpip_input) == NULL) {
DEBUG("Could not add atwinc15x0 device\n");
return;
}
#else /* MODULE_LWIP_IPV4 */
if (netif_add(&netif[0], &atwinc15x0_devs[i], lwip_netdev_init,
tcpip_input) == NULL) {
DEBUG("Could not add atwinc15x0 device\n");
return;
}
#endif /* MODULE_LWIP_IPV4 */
}
#elif defined(MODULE_ENC28J60)
for (unsigned i = 0; i < LWIP_NETIF_NUMOF; i++) {
enc28j60_setup(&enc28j60_devs[i], &enc28j60_params[i]);

View File

@ -729,6 +729,17 @@ typedef enum {
*/
NETOPT_LINK_CHECK,
/**
* @brief (int8_t) Received Signal Strength Indicator (RSSI)
*
* The RSSI is an indicator for the received field strength in wireless
* channels. It is often represented as the ratio of received power to
* a given unit, for example milliwatts. With a device-dependent scaling
* factor, the RSSI value can be expressed as power level in the unit
* dBm or ASU (Arbitrary Strength Unit).
*/
NETOPT_RSSI,
/**
* @brief maximum number of options defined here.
*

View File

@ -120,6 +120,7 @@ static const char *_netopt_strmap[] = {
[NETOPT_DEMOD_MARGIN] = "NETOPT_DEMOD_MARGIN",
[NETOPT_NUM_GATEWAYS] = "NETOPT_NUM_GATEWAYS",
[NETOPT_LINK_CHECK] = "NETOPT_LINK_CHECK",
[NETOPT_RSSI] = "NETOPT_RSSI",
[NETOPT_NUMOF] = "NETOPT_NUMOF",
};

View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2020 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup sys_auto_init_gnrc_netif
* @{
*
* @file
* @brief Auto initialization for ATWINC15X0 WiFi devices
*
* @author Gunar Schorcht <gunar@schorcht.net>
*/
#ifdef MODULE_ATWINC15X0
#include "log.h"
#include "atwinc15x0.h"
#include "atwinc15x0_params.h"
#include "net/gnrc/netif/ethernet.h"
/**
* @brief Define stack parameters for the MAC layer thread
* @{
*/
#define ATWINC15X0_MAC_STACKSIZE (THREAD_STACKSIZE_DEFAULT)
#ifndef ATWINC15X0_MAC_PRIO
#define ATWINC15X0_MAC_PRIO (GNRC_NETIF_PRIO)
#endif
/*** @} */
/**
* @brief Find out how many of these devices we need to care for
*/
#define ATWINC15X0_NUM ARRAY_SIZE(atwinc15x0_params)
/**
* @brief Allocate memory for the device descriptors
* @{
*/
static atwinc15x0_t dev[ATWINC15X0_NUM];
/** @} */
static gnrc_netif_t _netif[ATWINC15X0_NUM];
/**
* @brief Stacks for the MAC layer threads
*/
static char stack[ATWINC15X0_NUM][ATWINC15X0_MAC_STACKSIZE];
void auto_init_atwinc15x0(void)
{
for (unsigned i = 0; i < ATWINC15X0_NUM; i++) {
LOG_DEBUG("[auto_init_netif] initializing atwinc15x0 #%u\n", i);
/* setup netdev device */
atwinc15x0_setup(&dev[i], &atwinc15x0_params[i]);
gnrc_netif_ethernet_create(&_netif[i], stack[i],
ATWINC15X0_MAC_STACKSIZE,
ATWINC15X0_MAC_PRIO, "atwinc15x0",
(netdev_t *)&dev[i]);
}
}
#else
typedef int dont_be_pedantic;
#endif /* MODULE_ATWINC15X0 */
/** @} */

View File

@ -42,6 +42,11 @@ void gnrc_netif_init_devs(void)
auto_init_at86rf2xx();
}
if (IS_USED(MODULE_ATWINC15X0)) {
extern void auto_init_atwinc15x0(void);
auto_init_atwinc15x0();
}
if (IS_USED(MODULE_MRF24J40)) {
extern void auto_init_mrf24j40(void);
auto_init_mrf24j40();

View File

@ -531,6 +531,7 @@ static void _netif_list(netif_t *iface)
uint16_t u16;
int16_t i16;
uint8_t u8;
int8_t i8;
int res;
netopt_state_t state;
unsigned line_thresh = 1;
@ -561,6 +562,10 @@ static void _netif_list(netif_t *iface)
if (res >= 0) {
printf(" NID: 0x%" PRIx16 " ", u16);
}
res = netif_get_opt(iface, NETOPT_RSSI, 0, &i8, sizeof(i8));
if (res >= 0) {
printf(" RSSI: %d ", i8);
}
#ifdef MODULE_GNRC_NETIF_CMD_LORA
res = netif_get_opt(iface, NETOPT_BANDWIDTH, 0, &u8, sizeof(u8));
if (res >= 0) {

View File

@ -0,0 +1,7 @@
# the driver to test
USEMODULE = atwinc15x0
# msp430-gcc doesn't support -Wno-discarded-qualifiers
FEATURES_BLACKLIST += arch_msp430
include ../driver_netdev_common/Makefile

View File

@ -0,0 +1,21 @@
BOARD_INSUFFICIENT_MEMORY := \
arduino-duemilanove \
arduino-leonardo \
arduino-mega2560 \
arduino-uno \
arduino-nano \
atmega328p \
i-nucleo-lrwan1 \
msb-430 \
msb-430h \
nucleo-f031k6 \
nucleo-f042k6 \
nucleo-f303k8 \
nucleo-f334r8 \
nucleo-l031k6 \
nucleo-l053r8 \
stm32f030f4-demo \
stm32f0discovery \
stm32l0538-disco \
waspmote-pro \
#

View File

@ -0,0 +1 @@
../driver_netdev_common/main.c