42 #define xSPI_ASSERT_CS() {gpio_set_pin_low(CONF_WINC_SPI_CS_GPIO);} 43 #define xSPI_DEASSERT_CS() {gpio_set_pin_high(CONF_WINC_SPI_CS_GPIO);} 45 #define SPI_ASSERT_CS() do {p_pio->PIO_CODR = 1 << (CONF_WINC_SPI_CS_GPIO & 0x1F);}while(0) 46 #define SPI_DEASSERT_CS() do {p_pio->PIO_SODR = 1 << (CONF_WINC_SPI_CS_GPIO & 0x1F);}while(0) 49 #define NM_BUS_MAX_TRX_SZ 4096 56 #ifdef CONF_WINC_USE_I2C 57 #define SLAVE_ADDRESS 0x60 60 #define I2C_TIMEOUT 100 79 return nm_i2c_write(tmp, sz1+sz2);
83 #ifdef CONF_WINC_USE_SPI 89 #define SPI_ASSERT_CS() do {p_pio_cs->PIO_CODR = 1 << (CONF_WINC_SPI_CS_GPIO & 0x1F);} while(0) 90 #undef SPI_DEASSERT_CS 91 #define SPI_DEASSERT_CS() do {p_pio_cs->PIO_SODR = 1 << (CONF_WINC_SPI_CS_GPIO & 0x1F);} while(0) 96 pdc_packet_t pdc_spi_tx_packet,pdc_spi_rx_packet;
100 pdc_spi_tx_packet.ul_addr =
NULL;
101 pdc_spi_rx_packet.ul_addr =
NULL;
102 pdc_spi_tx_packet.ul_size = u16Sz;
103 pdc_spi_rx_packet.ul_size = u16Sz;
106 pdc_spi_tx_packet.ul_addr = (uint32_t)pu8Mosi;
110 pdc_spi_rx_packet.ul_addr = (uint32_t)pu8Miso;
113 pdc_tx_init(g_p_spim_pdc, &pdc_spi_tx_packet,
NULL);
114 pdc_rx_init(g_p_spim_pdc, &pdc_spi_rx_packet,
NULL);
119 g_p_spim_pdc->PERIPH_PTCR = PERIPH_PTCR_RXTEN|PERIPH_PTCR_TXTEN;
128 g_p_spim_pdc->PERIPH_PTCR = PERIPH_PTCR_TXTDIS|PERIPH_PTCR_RXTDIS;
133 #elif (defined LOW_DELAY) 137 uint8 u8SkipMosi = 0, u8SkipMiso = 0;
185 uint8 u8SkipMosi = 0, u8SkipMiso = 0;
186 uint16_t txd_data = 0;
187 uint16_t rxd_data = 0;
232 #ifdef CONF_WINC_USE_I2C 234 #elif defined CONF_WINC_USE_SPI 290 #ifdef CONF_WINC_USE_I2C 293 s8Ret = nm_i2c_read(pstrParam->
pu8Buf, pstrParam->
u16Sz);
298 s8Ret = nm_i2c_write(pstrParam->
pu8Buf, pstrParam->
u16Sz);
306 #elif defined CONF_WINC_USE_SPI 315 M2M_ERR(
"invalide ioclt cmd\n");
330 #ifdef CONF_WINC_USE_I2C 333 #ifdef CONF_WINC_USE_SPI
NMI_API void m2m_memcpy(uint8 *pDst, uint8 *pSrc, uint32 sz)
Copy specified number of bytes from source buffer to destination buffer.
void nm_bsp_reset(void)
Reset WINC1500 SoC by setting CHIP_EN and RESET_N signals low, CHIP_EN high then RESET_N high...
static void spi_set_master_mode(Spi *p_spi)
Set SPI to Master mode.
void spi_set_clock_phase(Spi *p_spi, uint32_t ul_pcs_ch, uint32_t ul_phase)
Set Data Capture Phase.
Structure holding SPI R/W parameters.
Structure holding I2C special operation parameters.
static void spi_enable(Spi *p_spi)
Enable SPI.
This module contains common APIs declarations.
#define PIOA
(PIOA ) Base Address
#define CONF_WINC_SPI_CLOCK
signed char sint8
Range of values between -128 to 127.
static void ioport_set_pin_mode(ioport_pin_t pin, ioport_mode_t mode)
Set pin mode for one single IOPORT pin.
#define CONF_WINC_SPI_CS_FLAGS
spi_status_t spi_read(Spi *p_spi, uint16_t *us_data, uint8_t *p_pcs)
Read the received data and it's peripheral chip select value. While SPI works in fixed peripheral sel...
int16_t spi_set_baudrate_div(Spi *p_spi, uint32_t ul_pcs_ch, uint8_t uc_baudrate_divider)
Set Serial Clock Baud Rate divider value (SCBR).
#define CONF_WINC_SPI_MOSI_FLAGS
#define CONF_WINC_SPI_MOSI_GPIO
void spi_set_bits_per_transfer(Spi *p_spi, uint32_t ul_pcs_ch, uint32_t ul_bits)
Set number of bits per transfer.
This module contains WINC3400 bus wrapper APIs declarations.
Structure holding bus capabilities information.
void spi_set_clock_polarity(Spi *p_spi, uint32_t ul_pcs_ch, uint32_t ul_polarity)
Set clock default state.
sint8 nm_bus_init(uint8_t *pvinit, uint32 req_serial_number)
unsigned short uint16
Range of values between 0 to 65535.
#define SPI_TDR_TD(value)
#define CONF_WINC_SPI_POL
#define CONF_WINC_SPI_CLK_FLAGS
static void spi_reset(Spi *p_spi)
Reset SPI and set it to Slave mode.
static uint32_t sysclk_get_peripheral_hz(void)
Retrieves the current rate in Hz of the peripheral clocks.
void spi_enable_clock(Spi *p_spi)
Enable SPI clock.
#define NM_BUS_MAX_TRX_SZ
#define CONF_WINC_SPI_DLYBCT
#define SPI_CSR_BITS_8_BIT
(SPI_CSR[4]) 8 bits for transfer
spi_status_t spi_write(Spi *p_spi, uint16_t us_data, uint8_t uc_pcs, uint8_t uc_last)
Write the transmitted data with specified peripheral chip select value.
#define SPI_SR_TDRE
(SPI_SR) Transmit Data Register Empty (cleared by writing SPI_TDR)
sint8 nm_bus_deinit(void)
De-initialize the bus wrapper.
static void spi_disable_mode_fault_detect(Spi *p_spi)
Disable Mode Fault Detection.
void spi_set_peripheral_chip_select_value(Spi *p_spi, uint32_t ul_value)
Set Peripheral Chip Select (PCS) value.
#define NM_BUS_IOCTL_W_SPECIAL
#define CONF_WINC_SPI_PHA
#define SPI_DEASSERT_CS()
static void ioport_set_pin_dir(ioport_pin_t pin, enum ioport_direction dir)
Set direction for a single IOPORT pin.
static void ioport_enable_pin(ioport_pin_t pin)
Enable an IOPORT pin, based on a pin created with IOPORT_CREATE_PIN().
#define CONF_WINC_SPI_NPCS
#define CONF_WINC_SPI_DLYBS
void spi_set_transfer_delay(Spi *p_spi, uint32_t ul_pcs_ch, uint8_t uc_dlybs, uint8_t uc_dlybct)
Configure timing for SPI transfer.
#define CONF_WINC_SPI_MISO_GPIO
unsigned long uint32
Range of values between 0 to 4294967295.
This module contains WINC3400 BSP APIs declarations.
sint8 nm_bus_ioctl(uint8 u8Cmd, void *pvParameter)
#define SPI_SR_RDRF
(SPI_SR) Receive Data Register Full (cleared by reading SPI_RDR)
unsigned char uint8
Range of values between 0 to 255.
Autogenerated API include file for the Atmel Software Framework (ASF)
static void spi_disable(Spi *p_spi)
Disable SPI.
#define CONF_WINC_SPI_MISO_FLAGS
#define SPI_RDR_RD_Msk
(SPI_RDR) Receive Data
tstrNmBusCapabilities egstrNmBusCapabilities
static void ioport_disable_pin(ioport_pin_t pin)
Disable IOPORT pin, based on a pin created with IOPORT_CREATE_PIN().
Structure holding I2C default operation parameters.
#define CONF_WINC_SPI_CLK_GPIO
#define CONF_WINC_SPI_CS_GPIO