nm_bus_wrapper_same70.c
Go to the documentation of this file.
1 
35 #include <stdio.h>
36 #include "bsp/include/nm_bsp.h"
39 #include "asf.h"
40 #include "conf_winc.h"
41 
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);}
44 
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)
47 
48 
49 #define NM_BUS_MAX_TRX_SZ 4096
50 
52 {
54 };
55 
56 #ifdef CONF_WINC_USE_I2C
57 #define SLAVE_ADDRESS 0x60
58 
60 #define I2C_TIMEOUT 100
61 
62 static sint8 nm_i2c_write(uint8 *b, uint16 sz)
63 {
64  sint8 result = M2M_ERR_BUS_FAIL;
65  return result;
66 }
67 
68 static sint8 nm_i2c_read(uint8 *rb, uint16 sz)
69 {
70  sint8 result = M2M_ERR_BUS_FAIL;
71  return result;
72 }
73 
74 static sint8 nm_i2c_write_special(uint8 *wb1, uint16 sz1, uint8 *wb2, uint16 sz2)
75 {
76  static uint8 tmp[NM_BUS_MAX_TRX_SZ];
77  m2m_memcpy(tmp, wb1, sz1);
78  m2m_memcpy(&tmp[sz1], wb2, sz2);
79  return nm_i2c_write(tmp, sz1+sz2);
80 }
81 #endif
82 
83 #ifdef CONF_WINC_USE_SPI
84 
85 Pio *p_pio_cs;
86 
88 #undef SPI_ASSERT_CS
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)
92 
93 static sint8 spi_rw(uint8 *pu8Mosi, uint8 *pu8Miso, uint16 u16Sz)
94 {
95 #ifdef DMA_SPI
96  pdc_packet_t pdc_spi_tx_packet,pdc_spi_rx_packet;
97 
98  p_pio = (Pio *)((uint32_t)PIOA + (PIO_DELTA * (CONF_WINC_SPI_CS_GPIO >> 5)));
99 
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;
104 
105  if (pu8Mosi) {
106  pdc_spi_tx_packet.ul_addr = (uint32_t)pu8Mosi;
107  }
108 
109  if(pu8Miso) {
110  pdc_spi_rx_packet.ul_addr = (uint32_t)pu8Miso;
111  }
112 
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);
115 
116  /*Assert CS*/
117  SPI_ASSERT_CS();
118  /* Enable the RX and TX PDC transfer requests */
119  g_p_spim_pdc->PERIPH_PTCR = PERIPH_PTCR_RXTEN|PERIPH_PTCR_TXTEN;
120 
121  /* Waiting transfer done*/
122  while((CONF_WINC_SPI->SPI_SR & SPI_SR_RXBUFF) == 0);
123 
124  /*DEASSERT CS*/
125  SPI_DEASSERT_CS();
126 
127  /* Disable the RX and TX PDC transfer requests */
128  g_p_spim_pdc->PERIPH_PTCR = PERIPH_PTCR_TXTDIS|PERIPH_PTCR_RXTDIS;
129 
130 
131  return M2M_SUCCESS;
132 
133 #elif (defined LOW_DELAY)
134 
135 
136 uint8 u8Dummy = 0;
137 uint8 u8SkipMosi = 0, u8SkipMiso = 0;
138 
139 p_pio = (Pio *)((uint32_t)PIOA + (PIO_DELTA * (CONF_WINC_SPI_CS_GPIO >> 5)));
140 
141 if (!pu8Mosi) {
142  pu8Mosi = &u8Dummy;
143  u8SkipMosi = 1;
144 }
145 else if(!pu8Miso) {
146  /*RX must be zero*/
147  pu8Miso = &u8Dummy;
148  u8SkipMiso = 1;
149 }
150 else {
151  return M2M_ERR_BUS_FAIL;
152 }
153 
154 /*TX path*/
155 if(!u8SkipMosi)
156 {
157  SPI_ASSERT_CS();
158  while (u16Sz--)
159  {
160  CONF_WINC_SPI->SPI_TDR = SPI_TDR_TD((uint16)*pu8Mosi);
161  while (!(CONF_WINC_SPI->SPI_SR & SPI_SR_TDRE));
162  pu8Mosi++;
163  }
164  SPI_DEASSERT_CS();
165 }
166 /*RX path*/
167 if(!u8SkipMiso)
168 {
169  SPI_ASSERT_CS();
170  while (u16Sz--)
171  {
172 
173  CONF_WINC_SPI->SPI_TDR = SPI_TDR_TD((uint16)*pu8Mosi);
174  while (!(CONF_WINC_SPI->SPI_SR & SPI_SR_TDRE));
175  while (!(CONF_WINC_SPI->SPI_SR & (SPI_SR_RDRF)));
176  *pu8Miso = (uint16_t) ((CONF_WINC_SPI->SPI_RDR) & SPI_RDR_RD_Msk);
177  pu8Miso++;
178  }
179  SPI_DEASSERT_CS();
180 }
181 return M2M_SUCCESS;
182 
183 #else
184  uint8 u8Dummy = 0;
185  uint8 u8SkipMosi = 0, u8SkipMiso = 0;
186  uint16_t txd_data = 0;
187  uint16_t rxd_data = 0;
188  uint8_t uc_pcs;
189 
190  if (!pu8Mosi) {
191  pu8Mosi = &u8Dummy;
192  u8SkipMosi = 1;
193  }
194  else if(!pu8Miso) {
195  pu8Miso = &u8Dummy;
196  u8SkipMiso = 1;
197  }
198  else {
199  return M2M_ERR_BUS_FAIL;
200  }
201  SPI_ASSERT_CS();
202  while (u16Sz) {
203  txd_data = *pu8Mosi;
204 
205  spi_write(CONF_WINC_SPI, txd_data, 0, 0);
206  spi_read(CONF_WINC_SPI, &rxd_data, &uc_pcs);
207 
208  *pu8Miso = rxd_data;
209 
210  u16Sz--;
211  if (!u8SkipMiso)
212  pu8Miso++;
213  if (!u8SkipMosi)
214  pu8Mosi++;
215  }
216  SPI_DEASSERT_CS();
217 
218  return M2M_SUCCESS;
219  #endif
220 
221 }
222 #endif
223 
224 /*
225 * @fn nm_bus_init
226 * @brief Initialize the bus wrapper
227 * @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure
228 */
229 sint8 nm_bus_init(uint8_t *pvinit, uint32 req_serial_number)
230 {
231  sint8 result = M2M_SUCCESS;
232 #ifdef CONF_WINC_USE_I2C
233 
234 #elif defined CONF_WINC_USE_SPI
235  /* Configure SPI pins. */
243 
244  /* Configure CS for manual (GPIO) control. */
245  p_pio_cs = (Pio *)((uint32_t)PIOA + (PIO_DELTA * (CONF_WINC_SPI_CS_GPIO >> 5)));
246  SPI_DEASSERT_CS();
249 
258 
260 
262 
263  //printf("sys clk %d\r\n",sysclk_get_cpu_hz());
269 
270  nm_bsp_reset();
271 #endif
272  return result;
273 }
274 
275 /*
276 * @fn nm_bus_ioctl
277 * @brief send/receive from the bus
278 * @param[IN] u8Cmd
279 * IOCTL command for the operation
280 * @param[IN] pvParameter
281 * Arbitrary parameter depenging on IOCTL
282 * @return M2M_SUCCESS in case of success and M2M_ERR_BUS_FAIL in case of failure
283 * @note For SPI only, it's important to be able to send/receive at the same time
284 */
285 sint8 nm_bus_ioctl(uint8 u8Cmd, void* pvParameter)
286 {
287  sint8 s8Ret = 0;
288  switch(u8Cmd)
289  {
290 #ifdef CONF_WINC_USE_I2C
291  case NM_BUS_IOCTL_R: {
292  tstrNmI2cDefault *pstrParam = (tstrNmI2cDefault *)pvParameter;
293  s8Ret = nm_i2c_read(pstrParam->pu8Buf, pstrParam->u16Sz);
294  }
295  break;
296  case NM_BUS_IOCTL_W: {
297  tstrNmI2cDefault *pstrParam = (tstrNmI2cDefault *)pvParameter;
298  s8Ret = nm_i2c_write(pstrParam->pu8Buf, pstrParam->u16Sz);
299  }
300  break;
301  case NM_BUS_IOCTL_W_SPECIAL: {
302  tstrNmI2cSpecial *pstrParam = (tstrNmI2cSpecial *)pvParameter;
303  s8Ret = nm_i2c_write_special(pstrParam->pu8Buf1, pstrParam->u16Sz1, pstrParam->pu8Buf2, pstrParam->u16Sz2);
304  }
305  break;
306 #elif defined CONF_WINC_USE_SPI
307  case NM_BUS_IOCTL_RW: {
308  tstrNmSpiRw *pstrParam = (tstrNmSpiRw *)pvParameter;
309  s8Ret = spi_rw(pstrParam->pu8InBuf, pstrParam->pu8OutBuf, pstrParam->u16Sz);
310  }
311  break;
312 #endif
313  default:
314  s8Ret = -1;
315  M2M_ERR("invalide ioclt cmd\n");
316  break;
317  }
318 
319  return s8Ret;
320 }
321 
322 /*
323 * @fn nm_bus_deinit
324 * @brief De-initialize the bus wrapper
325 */
327 {
328  sint8 result = M2M_SUCCESS;
329 
330 #ifdef CONF_WINC_USE_I2C
331  //TODO:
332 #endif /* CONF_WINC_USE_I2C */
333 #ifdef CONF_WINC_USE_SPI
339 #endif /* CONF_WINC_USE_SPI */
340  return result;
341 }
uint8 * pu8InBuf
NMI_API void m2m_memcpy(uint8 *pDst, uint8 *pSrc, uint32 sz)
Copy specified number of bytes from source buffer to destination buffer.
Definition: nm_common.c:36
uint8 * pu8OutBuf
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.
Definition: spi.c:307
Structure holding SPI R/W parameters.
Structure holding I2C special operation parameters.
#define NM_BUS_IOCTL_R
static void spi_enable(Spi *p_spi)
Enable SPI.
This module contains common APIs declarations.
#define PIOA
(PIOA ) Base Address
Definition: same70j19.h:529
#define CONF_WINC_SPI_CLOCK
Definition: conf_winc.h:93
signed char sint8
Range of values between -128 to 127.
Definition: nm_bsp.h:111
static void ioport_set_pin_mode(ioport_pin_t pin, ioport_mode_t mode)
Set pin mode for one single IOPORT pin.
Definition: ioport.h:217
WINC3400 configuration.
#define CONF_WINC_SPI_CS_FLAGS
Definition: conf_winc.h:74
spi_status_t spi_read(Spi *p_spi, uint16_t *us_data, uint8_t *p_pcs)
Read the received data and it&#39;s peripheral chip select value. While SPI works in fixed peripheral sel...
Definition: spi.c:224
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).
Definition: spi.c:385
#define CONF_WINC_SPI_MOSI_FLAGS
Definition: conf_winc.h:70
#define CONF_WINC_SPI_MOSI_GPIO
Definition: conf_winc.h:69
#define M2M_SUCCESS
Definition: nm_common.h:51
#define NULL
Definition: nm_bsp.h:52
void spi_set_bits_per_transfer(Spi *p_spi, uint32_t ul_pcs_ch, uint32_t ul_bits)
Set number of bits per transfer.
Definition: spi.c:345
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.
Definition: spi.c:290
sint8 nm_bus_init(uint8_t *pvinit, uint32 req_serial_number)
unsigned short uint16
Range of values between 0 to 65535.
Definition: nm_bsp.h:96
#define SPI_TDR_TD(value)
#define CONF_WINC_SPI_POL
Definition: conf_winc.h:89
#define CONF_WINC_SPI_CLK_FLAGS
Definition: conf_winc.h:72
static void spi_reset(Spi *p_spi)
Reset SPI and set it to Slave mode.
#define SPI_ASSERT_CS()
static uint32_t sysclk_get_peripheral_hz(void)
Retrieves the current rate in Hz of the peripheral clocks.
#define PIO_DELTA
void spi_enable_clock(Spi *p_spi)
Enable SPI clock.
Definition: spi.c:60
#define NM_BUS_MAX_TRX_SZ
#define CONF_WINC_SPI_DLYBCT
Definition: conf_winc.h:79
#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.
Definition: spi.c:257
#define SPI_SR_TDRE
(SPI_SR) Transmit Data Register Empty (cleared by writing SPI_TDR)
#define M2M_ERR(...)
Definition: nm_debug.h:80
Pio hardware registers.
#define NM_BUS_IOCTL_RW
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.
Definition: spi.c:193
#define NM_BUS_IOCTL_W_SPECIAL
#define CONF_WINC_SPI_PHA
Definition: conf_winc.h:90
#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.
Definition: ioport.h:263
static void ioport_enable_pin(ioport_pin_t pin)
Enable an IOPORT pin, based on a pin created with IOPORT_CREATE_PIN().
Definition: ioport.h:156
#define CONF_WINC_SPI_NPCS
Definition: conf_winc.h:75
#define CONF_WINC_SPI_DLYBS
Definition: conf_winc.h:78
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.
Definition: spi.c:405
#define CONF_WINC_SPI_MISO_GPIO
Definition: conf_winc.h:67
unsigned long uint32
Range of values between 0 to 4294967295.
Definition: nm_bsp.h:103
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.
Definition: nm_bsp.h:89
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
Definition: conf_winc.h:68
#define SPI_RDR_RD_Msk
(SPI_RDR) Receive Data
tstrNmBusCapabilities egstrNmBusCapabilities
#define CONF_WINC_SPI
Definition: conf_winc.h:65
static void ioport_disable_pin(ioport_pin_t pin)
Disable IOPORT pin, based on a pin created with IOPORT_CREATE_PIN().
Definition: ioport.h:179
Structure holding I2C default operation parameters.
#define NM_BUS_IOCTL_W
#define CONF_WINC_SPI_CLK_GPIO
Definition: conf_winc.h:71
#define CONF_WINC_SPI_CS_GPIO
Definition: conf_winc.h:73
#define M2M_ERR_BUS_FAIL
Definition: nm_common.h:57


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:04