communications.cpp
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright 2014-2019 Inertial Sense, Inc. - http://inertialsense.com
5 
6 Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files(the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions :
7 
8 The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
9 
10 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT, IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 #include <asf.h>
14 #include "../../../src/ISUtilities.h"
15 #include "../../../src/ISLogger.h"
16 #include "../../../hw-libs/misc/bootloaderApp.h"
17 #include "../drivers/d_quadEnc.h"
18 #include "ISLogFileFatFs.h"
19 #include "xbee.h"
20 #include "wifi.h"
21 #include "sd_card_logger.h"
22 #include "communications.h"
23 #include "CAN.h"
24 #include "../hw-libs/communications/CAN_comm.h"
25 #include "../src/protocol_nmea.h"
26 
27 typedef struct
28 {
29  // Comm instances
31 
32  // Comm instance data buffer
33  uint8_t comm_buffer[PKT_BUF_SIZE];
34 
36 
37 
38 #define COM_RX_PORT_COUNT (EVB2_PORT_COUNT-1) // exclude CAN port
40 static uint8_t s_rxDecodeBuffer[PKT_BUF_SIZE] = {};
41 
45 
46 int comWrite(int serialNum, const unsigned char *buf, int size, uint32_t ledPin )
47 {
48  int len;
50  {
51  len = spiTouINS_serWrite(buf, size);
52  }
53  else
54  {
55  len = serWrite(serialNum, buf, size);
56  }
57 
58  if(len)
59  {
60  LED_ON(ledPin);
61  }
62  return len;
63 }
64 
65 int comRead(int serialNum, unsigned char *buf, int bufSize, uint32_t ledPin)
66 {
67  int len = 0;
68 
70  {
71  len = spiTouINS_serRead(buf, bufSize);
72  }
73  else
74  {
75 #if 0 // Wait for end of data. Check Rx buffer has data and hasn't change over 1ms.
76  static int usedLast[EVB2_PORT_COUNT] = {0};
77  int used = serRxUsed(serialNum);
78  if(used!=0 && used==usedLast[serialNum])
79  { // Data in Rx buffer and amount hasn't changed.
80  len = serRead(serialNum, buf, bufSize, 0);
81  }
82  usedLast[serialNum] = used;
83 #else
84  // Normal read
85  len = serRead(serialNum, buf, bufSize);
86 #endif
87  }
88 
89  if(len)
90  {
91  LED_ON(ledPin);
92  }
93  return len;
94 }
95 
97 {
98  UNUSED(port);
99 #if 0
100  uint32_t stopbits, parity, databits;
101 // uint32_t imr;
102 
103  switch (cfg->bCharFormat)
104  {
105  case CDC_STOP_BITS_2:
106  stopbits = US_MR_NBSTOP_2_BIT;
107  break;
108  case CDC_STOP_BITS_1_5:
109  stopbits = US_MR_NBSTOP_1_5_BIT;
110  break;
111  case CDC_STOP_BITS_1:
112  default:
113  // Default stop bit = 1 stop bit
114  stopbits = US_MR_NBSTOP_1_BIT;
115  break;
116  }
117 
118  switch (cfg->bParityType)
119  {
120  case CDC_PAR_EVEN:
121  parity = US_MR_PAR_EVEN;
122  break;
123  case CDC_PAR_ODD:
124  parity = US_MR_PAR_ODD;
125  break;
126  case CDC_PAR_MARK:
127  parity = US_MR_PAR_MARK;
128  break;
129  case CDC_PAR_SPACE:
130  parity = US_MR_PAR_SPACE;
131  break;
132  default:
133  case CDC_PAR_NONE:
134  parity = US_MR_PAR_NO;
135  break;
136  }
137 
138  switch(cfg->bDataBits)
139  {
140  case 5:
141  case 6:
142  case 7:
143  databits = cfg->bDataBits - 5;
144  break;
145  default:
146  case 8:
147  databits = US_MR_CHRL_8_BIT;
148  break;
149  }
150 
151  // Options for USART. This gets called when USB is first connected AND each time the USB CDC serial port is opened by the host.
152  // sam_usart_opt_t usart_options;
153  // usart_options.baudrate = LE32_TO_CPU(cfg->dwDTERate);
154  // usart_options.char_length = databits;
155  // usart_options.parity_type = parity;
156  // usart_options.stop_bits = stopbits;
157  // usart_options.channel_mode = US_MR_CHMODE_NORMAL;
158 #endif
159 
160  uint32_t baudrate = LE32_TO_CPU(cfg->dwDTERate);
161  if (comManagerValidateBaudRate(baudrate)==0)
162  {
163  // Set baudrate based on USB CDC baudrate
165  {
166  serSetBaudRate(EVB2_PORT_UINS0, baudrate);
167  }
168 
171  {
172  serSetBaudRate(EVB2_PORT_UINS1, baudrate);
173  }
174  }
175 
176  if (comManagerValidateBaudRate(baudrate)==0 || baudrate==9600)
177  {
178  // if(g_flashCfg->cbf[EVB2_PORT_USB] & (1<<EVB2_PORT_XBEE))
179  // {
180  // serSetBaudRate(EVB2_PORT_XBEE, baudrate);
181  // }
183  {
184  serSetBaudRate(EVB2_PORT_XRADIO, baudrate);
185  }
187  {
188  serSetBaudRate(EVB2_PORT_BLE, baudrate);
189  }
191  {
192  serSetBaudRate(EVB2_PORT_SP330, baudrate);
193  }
195  {
197  }
198  }
199 
200 }
201 
202 void callback_cdc_set_dtr(uint8_t port, bool b_enable)
203 {
204  if (b_enable)
205  { // Host terminal has open COM
207  }
208  else
209  { // Host terminal has close COM
211  }
212 
214  {
215  if (b_enable)
216  { // Assert (LOW) DTR
219  }
220  else
221  { // De-assert (HIGH) DTR
224  }
225  }
226 }
227 
228 // This function never gets called because of a bug in Atmel CDC driver. Bummer.
229 // void callback_cdc_set_rts(uint8_t port, bool b_enable)
230 // {
231 // switch(g_msg.evb.comBridgeCfg)
232 // {
233 // case EVB2_CBC_USBxXBEE:
234 // if (b_enable)
235 // {
236 // ioport_set_pin_level(UART_XBEE_N_RTS_PIN, IOPORT_PIN_LEVEL_HIGH);
237 // }
238 // else
239 // {
240 // ioport_set_pin_level(UART_XBEE_N_RTS_PIN, IOPORT_PIN_LEVEL_LOW);
241 // }
242 // break;
243 //
244 // case EVB2_CBC_RS232xUSB:
245 // case EVB2_CBC_RS422xUSB:
246 // break;
247 // }
248 // }
249 
250 
252 {
253  int len = is_comm_stop_broadcasts_current_port(&comm);
255 }
256 
258 {
259  int len;
260 
261  len = is_comm_get_data(&comm, DID_INS_2, 0, 0, 10); // 20 x 4ms = 40ms
263 
264  len = is_comm_get_data(&comm, DID_DEV_INFO, 0, 0, 500); // 500ms
266 }
267 
269 {
270  rmc_t rmc;
272  rmc.options = 0;
273  int len = is_comm_set_data(&comm, DID_RMC, 0, sizeof(rmc_t), &rmc);
275 
276 // len = is_comm_get_data(&comm, DID_INS_2, 0, 0, 1); // 1 x 4ms = 4ms
277 // comWrite(EVB2_PORT_UINS0, comm.buffer, len, LED_INS_TXD_PIN);
278 }
279 
280 
281 void handle_data_from_uINS(p_data_hdr_t &dataHdr, uint8_t *data)
282 {
283  uDatasets d;
284 
285  // Save uINS data to global variables
286  switch(dataHdr.id)
287  {
288  case DID_DEV_INFO:
289  copyDataPToStructP2(&g_msg.uInsInfo, &dataHdr, data, sizeof(dev_info_t));
290  break;
291 
292  case DID_INS_1:
293  copyDataPToStructP2(&d, &dataHdr, data, sizeof(ins_1_t));
294  g_status.week = d.ins1.week;
295  g_status.timeOfWeekMs = (uint32_t)(d.ins1.timeOfWeek*1000);
296  break;
297 
298  case DID_INS_2:
299  copyDataPToStructP2(&g_msg.ins2, &dataHdr, data, sizeof(ins_2_t));
301  g_status.timeOfWeekMs = (uint32_t)(g_msg.ins2.timeOfWeek*1000);
302  break;
303 
304  case DID_INS_3:
305  copyDataPToStructP2(&d, &dataHdr, data, sizeof(ins_3_t));
306  g_status.week = d.ins1.week;
307  g_status.timeOfWeekMs = (uint32_t)(d.ins3.timeOfWeek*1000);
308  break;
309 
310  case DID_INS_4:
311  copyDataPToStructP2(&d, &dataHdr, data, sizeof(ins_4_t));
312  g_status.week = d.ins4.week;
313  g_status.timeOfWeekMs = (uint32_t)(d.ins4.timeOfWeek*1000);
314  break;
315  }
316 }
317 
318 
320 {
321  is_evb_log_stream stm = {};
322  uint8_t data[MAX_DATASET_SIZE];
323  p_data_hdr_t dataHdr = {};
324 
325  while (xStreamBufferReceive(g_xStreamBufferUINS, (void*)&stm, sizeof(is_evb_log_stream), 0) == sizeof(is_evb_log_stream))
326  {
327  if (stm.marker==DATA_CHUNK_MARKER)
328  {
329  switch (stm.ptype)
330  {
332  if (xStreamBufferReceive(g_xStreamBufferUINS, (void*)&dataHdr, sizeof(p_data_hdr_t), 0) == sizeof(p_data_hdr_t))
333  {
334  if (dataHdr.id < DID_COUNT && dataHdr.size < MAX_DATASET_SIZE)
335  {
336  if (xStreamBufferReceive(g_xStreamBufferUINS, (void*)data, dataHdr.size, 0) == dataHdr.size)
337  {
338  // Log Inertial Sense Binary data to SD Card
339  if(g_loggerEnabled)
340  {
341  logger.LogData(0, &dataHdr, data);
342  }
343  }
344  }
345  }
346  break;
347 
348  case _PTYPE_ASCII_NMEA:
349  break;
350 
351  case _PTYPE_UBLOX:
352 #if UBLOX_LOG_ENABLE
353  if (xStreamBufferReceive(g_xStreamBufferUINS, (void*)&data, stm.size, 0) == stm.size)
354  {
355 extern void log_ublox_raw_to_SD(cISLogger& logger, uint8_t *dataPtr, uint32_t dataSize);
356  log_ublox_raw_to_SD(logger, data, stm.size);
357  }
358 #endif
359  break;
360  }
361  }
362  }
363 }
364 
365 
367 {
368  if(error_check_config(&newCfg))
369  {
370  return;
371  }
372 
373  // Data is identical, no changes.
374  if( !memcmp(&newCfg, g_flashCfg, sizeof(evb_flash_cfg_t)) )
375  {
376  return;
377  }
378 
379  bool initCbPreset = false;
380  bool initIOconfig = false;
381  bool reinitXBee = false;
382  bool reinitWiFi = false;
383 
384  // Detect changes
385  if (newCfg.cbPreset != g_flashCfg->cbPreset ||
387  {
388  initCbPreset = true;
389  initIOconfig = true;
390  }
391  if (newCfg.radioPID != g_flashCfg->radioPID ||
392  newCfg.radioNID != g_flashCfg->radioNID ||
394  {
395  reinitXBee = true;
396  }
399  { // WiFi or TCP server preset changed
400  reinitWiFi = true;
401  }
402  int i = EVB_CFG_BITS_IDX_WIFI(newCfg.bits);
403  if (strncmp((const char*)(newCfg.wifi[i].ssid), (const char*)(g_flashCfg->wifi[i].ssid), WIFI_SSID_PSK_SIZE)!=0 ||
404  strncmp((const char*)(newCfg.wifi[i].psk), (const char*)(g_flashCfg->wifi[i].psk), WIFI_SSID_PSK_SIZE)!=0 ||
405  newCfg.server[i].ipAddr != g_flashCfg->server[i].ipAddr ||
406  newCfg.server[i].port != g_flashCfg->server[i].port)
407  { // WiFi or TCP settings changed
408  reinitWiFi = true;
409  }
410  i = EVB_CFG_BITS_IDX_SERVER(newCfg.bits);
411  if (newCfg.server[i].ipAddr != g_flashCfg->server[i].ipAddr ||
412  newCfg.server[i].port != g_flashCfg->server[i].port)
413  { // TCP settings changed
414  reinitWiFi = true;
415  }
421  {
422  initIOconfig = true;
423  }
424  if (g_flashCfg->CANbaud_kbps != newCfg.CANbaud_kbps)
425  {
427  CAN_init();
428  }
430  {
432  CAN_init();
433  }
434 
435  // Copy data from message to working location
436  *g_flashCfg = newCfg;
437 
438  // Apply changes
439  if(initCbPreset)
440  {
442  }
443  if(initIOconfig)
444  { // Update EVB IO config
445  board_IO_config();
446  }
447  if(reinitXBee)
448  {
449  xbee_init();
450  }
451  if(reinitWiFi)
452  {
453  wifi_reinit();
454  }
455  refresh_CFG_LED();
456 
457  // Enable flash write
460 }
461 
462 
464 {
465  uint8_t *dataPtr = comm->dataPtr + comm->dataHdr.offset;
466 
467  switch(ptype)
468  {
470  switch(comm->dataHdr.id)
471  { // From host to EVB
472  case DID_EVB_STATUS:
474  break;
475 
476  case DID_EVB_FLASH_CFG:
477  evb_flash_cfg_t newCfg;
478  newCfg = *g_flashCfg;
479  is_comm_copy_to_struct(&newCfg, comm, sizeof(evb_flash_cfg_t));
480 
481  update_flash_cfg(newCfg);
482  break;
483 
484  case DID_EVB_DEBUG_ARRAY:
486  break;
487  }
488 
489  // Disable uINS bootloader if host sends IS binary data
491  break;
492 
494  if(comm->pkt.hdr.pid == PID_GET_DATA)
495  {
496  int n=0;
497  is_comm_instance_t commTx;
498  uint8_t buffer[MAX_DATASET_SIZE];
499  is_comm_init(&commTx, buffer, sizeof(buffer));
500  switch(comm->dataHdr.id)
501  {
502  case DID_DEV_INFO: n = is_comm_data(&commTx, DID_EVB_DEV_INFO, 0, sizeof(dev_info_t), (void*)&(g_evbDevInfo)); break;
503  case DID_EVB_STATUS: n = is_comm_data(&commTx, DID_EVB_STATUS, 0, sizeof(evb_status_t), (void*)&(g_status)); break;
504  case DID_EVB_FLASH_CFG: n = is_comm_data(&commTx, DID_EVB_FLASH_CFG, 0, sizeof(evb_flash_cfg_t), (void*)(g_flashCfg)); break;
505  case DID_EVB_DEBUG_ARRAY: n = is_comm_data(&commTx, DID_EVB_DEBUG_ARRAY, 0, sizeof(debug_array_t), (void*)&(g_debug)); break;
506  case DID_EVB_RTOS_INFO: n = is_comm_data(&commTx, DID_EVB_RTOS_INFO, 0, sizeof(evb_rtos_info_t), (void*)&(g_rtos)); g_enRtosStats = true; break;
507  }
508  if(n>0)
509  {
510  serWrite(EVB2_PORT_USB, commTx.buf.start, n);
511  }
512 
513  // Disable uINS bootloader mode if host sends IS binary command
515  }
516  break;
517 
518  case _PTYPE_ASCII_NMEA:
519  {
520  uint32_t messageIdUInt = ASCII_MESSAGEID_TO_UINT(&(dataPtr[1]));
521  if(comm->dataHdr.size == 10)
522  { // 4 character commands (i.e. "$STPB*14\r\n")
523  switch (messageIdUInt)
524  {
525  case ASCII_MSG_ID_BLEN: // Enable bootloader (uINS)
527  break;
528 
529  case ASCII_MSG_ID_EBLE: // Enable bootloader (EVB)
530  // Disable uINS bootloader if host enables EVB bootloader
532 
534  break;
535  }
536  break;
537  }
538  else
539  { // General ASCII
540  switch (messageIdUInt)
541  {
542  case ASCII_MSG_ID_NELB: // SAM bootloader assistant (SAM-BA) enable
543  if (comm->dataHdr.size == 22 &&
544 // (pHandle == EVB2_PORT_USB) &&
545  strncmp((const char*)(&(comm->buf.start[6])), "!!SAM-BA!!", 6) == 0)
546  { // 16 character commands (i.e. "$NELB,!!SAM-BA!!\0*58\r\n")
548  }
549  break;
550 
551  default:
552  // Disable uINS bootloader if host sends larger ASCII sentence
554  break;
555  }
556  }
557  }
558  break;
559  }
560 
561 }
562 
563 
564 #define CAN_COM_PORT 1
565 #define CAN_HDR 0xFC;
566 #define CAN_FTR 0xFE;
567 
568 void sendRadio(uint8_t *data, int dataSize, bool sendXbee, bool sendXrad)
569 {
571  { // Filter RTK Base Messages
572  protocol_type_t ptype;
573 
574  static is_comm_instance_t comm = {};
575  static uint8_t buffer[PKT_BUF_SIZE];
576  if (comm.buf.start == NULL)
577  { // Init buffer
578  is_comm_init(&comm, buffer, sizeof(buffer));
579  }
580 
581  for(uint8_t *ptr=data; dataSize>0; )
582  {
583  // Number of bytes to copy
584  int n = _MIN(dataSize, is_comm_free(&comm));
585 
586  // Copy data into buffer
587  memcpy(comm.buf.tail, ptr, n);
588  comm.buf.tail += n;
589  dataSize -= n;
590  ptr += n;
591 
592  while((ptype = is_comm_parse(&comm)) != _PTYPE_NONE)
593  {
594  // Parse Data
595  switch(ptype)
596  {
597  case _PTYPE_UBLOX:
598  case _PTYPE_RTCM3:
599  case _PTYPE_ASCII_NMEA:
600  if(sendXbee){ comWrite(EVB2_PORT_XBEE, comm.dataPtr, comm.dataHdr.size, LED_XBEE_TXD_PIN); }
601  if(sendXrad){ comWrite(EVB2_PORT_XRADIO, comm.dataPtr, comm.dataHdr.size, 0); }
602  break;
603  }
604  }
605  }
606  }
607  else
608  {
609  if(sendXbee){ comWrite(EVB2_PORT_XBEE, data, dataSize, LED_XBEE_TXD_PIN); }
610  if(sendXrad){ comWrite(EVB2_PORT_XRADIO, data, dataSize, 0); }
611  }
612 }
613 
614 
615 // This function only forwards data after complete valid packets are received
616 void com_bridge_smart_forward(uint32_t srcPort, uint32_t ledPin)
617 {
618  if(srcPort>=COM_RX_PORT_COUNT)
619  {
620  return;
621  }
622 
623  is_comm_instance_t &comm = g_comRxPort[srcPort].comm;
624 
625  // Get available size of comm buffer
626  int n = is_comm_free(&comm);
627 
628  if ((n = comRead(srcPort, comm.buf.tail, n, ledPin)) > 0)
629  {
631  { // When uINS bootloader is enabled forwarding is disabled below is_comm_parse(), so forward bootloader data here.
632  switch (srcPort)
633  {
635  case EVB2_PORT_UINS0: comWrite(EVB2_PORT_USB, comm.buf.tail, n, 0); break;
636  }
637  }
638 
639  // Update comm buffer tail pointer
640  comm.buf.tail += n;
641 
642  // Search comm buffer for valid packets
643  protocol_type_t ptype;
644  while((ptype = is_comm_parse(&comm)) != _PTYPE_NONE)
645  {
646  switch(srcPort)
647  {
648  case EVB2_PORT_USB:
649  case EVB2_PORT_XBEE:
650  handle_data_from_host(&comm, ptype);
651  break;
652  }
653 
654  if (ptype!=_PTYPE_NONE &&
655  ptype!=_PTYPE_PARSE_ERROR &&
657  { // Forward data
658  uint32_t pktSize = _MIN(comm.buf.scan - comm.pktPtr, PKT_BUF_SIZE);
659  com_bridge_forward(srcPort, comm.pktPtr, pktSize);
660 
661  // Send uINS data to Logging task
662  if (srcPort == g_flashCfg->uinsComPort)
663  {
664  is_evb_log_stream stm;
666  stm.ptype = ptype;
667  switch (ptype)
668  {
671 
672  stm.size = sizeof(p_data_hdr_t) + comm.dataHdr.size;
673  xStreamBufferSend(g_xStreamBufferUINS, (void*)&(stm), sizeof(is_evb_log_stream), 0);
674  xStreamBufferSend(g_xStreamBufferUINS, (void*)&(comm.dataHdr), sizeof(p_data_hdr_t), 0);
675  xStreamBufferSend(g_xStreamBufferUINS, (void*)(comm.dataPtr), comm.dataHdr.size, 0);
676  break;
677  case _PTYPE_UBLOX:
678 #if UBLOX_LOG_ENABLE
679  stm.size = pktSize;
680  xStreamBufferSend(g_xStreamBufferUINS, (void*)&(stm), sizeof(is_evb_log_stream), 0);
681  xStreamBufferSend(g_xStreamBufferUINS, (void*)(comm.pktPtr), pktSize, 0);
682 #endif
683  break;
684  }
685  }
686  }
687  }
688  }
689 }
690 
691 
692 void com_bridge_smart_forward_xstream(uint32_t srcPort, StreamBufferHandle_t xStreamBuffer);
693 void com_bridge_smart_forward_xstream(uint32_t srcPort, StreamBufferHandle_t xStreamBuffer)
694 {
695  if(srcPort>=COM_RX_PORT_COUNT)
696  {
697  return;
698  }
699 
700  is_comm_instance_t &comm = g_comRxPort[srcPort].comm;
701 
702  // Get available size of comm buffer
703  int n = is_comm_free(&comm);
704 
705  if ((n = xStreamBufferReceive(xStreamBuffer, comm.buf.tail, n, 0)) > 0)
706  {
707  // Update comm buffer tail pointer
708  comm.buf.tail += n;
709 
710  // Search comm buffer for valid packets
711  protocol_type_t ptype;
712  while ((ptype = is_comm_parse(&comm)) != _PTYPE_NONE)
713  {
714  if (srcPort == EVB2_PORT_USB)
715  {
716  handle_data_from_host(&comm, ptype);
717  }
718 
719  if (ptype!=_PTYPE_NONE &&
720  ptype!=_PTYPE_PARSE_ERROR &&
722  { // Forward data
723  uint32_t pktSize = _MIN(comm.buf.scan - comm.pktPtr, PKT_BUF_SIZE);
724  com_bridge_forward(srcPort, comm.pktPtr, pktSize);
725  }
726  }
727  }
728 }
729 
730 
731 void com_bridge_forward(uint32_t srcPort, uint8_t *buf, int len)
732 {
733  uint32_t dstCbf = g_flashCfg->cbf[srcPort];
734 
735  if(dstCbf == 0 || len==0) // None
736  {
737  return;
738  }
739 
741  { // uINS bootloader mode enabled - don't allow forwarding on these ports
742  if(dstCbf & (1<<EVB2_PORT_USB))
743  {
744  comWrite(EVB2_PORT_USB, buf, len, 0);
745  }
746 
747  if(dstCbf & (1<<EVB2_PORT_UINS0))
748  {
750  }
751  }
752 
753  if(dstCbf & (1<<EVB2_PORT_UINS1))
754  {
756  }
757 
758  bool sendXbee = dstCbf & (1<<EVB2_PORT_XBEE) && xbee_runtime_mode(); // Disable XBee communications when being configured
759  bool sendXradio = dstCbf & (1<<EVB2_PORT_XRADIO);
760  if(sendXbee || sendXradio)
761  {
762  sendRadio(buf, len, sendXbee, sendXradio);
763  }
764 
765  if(dstCbf & (1<<EVB2_PORT_BLE))
766  {
768  }
769 
770  if(dstCbf & (1<<EVB2_PORT_SP330))
771  {
773  }
774 
775  if(dstCbf & (1<<EVB2_PORT_GPIO_H8))
776  {
778  }
779 
780 #if 0 // Disabled when forwarding data directly in wifi task
781  if(dstCbf & (1<<EVB2_PORT_WIFI))
782  {
783  xStreamBufferSend(g_xStreamBufferWiFiTx, (void*)buf, len, 0);
784  }
785 #endif
786 }
787 
788 
790 {
791  // USB CDC Rx =======================================================
793 
794  // uINS Ser0 Rx =======================================================
796 
797  // uINS Ser1 (TTL or SPI) Rx =======================================================
799 
800 #ifdef CONF_BOARD_SERIAL_XBEE // XBee Rx =======================================================
801  xbee_step(&comm);
802 #endif
803 
804 #ifdef CONF_BOARD_SERIAL_EXT_RADIO // External Radio Rx =======================================================
806 #endif
807 
808 #ifdef CONF_BOARD_SERIAL_ATWINC_BLE // ATWINC BLE Rx =======================================================
810 #endif
811 
812 #ifdef CONF_BOARD_SERIAL_SP330 // SP330 RS232/RS422 converter Rx =======================================================
814 #endif
815 
816 #ifdef CONF_BOARD_SERIAL_GPIO_H8 // H8 Header GPIO TTL Rx =======================================================
818 #endif
819 
820 #ifdef CONF_BOARD_SPI_ATWINC_WIFI // WiFi Rx =======================================================
822 #endif
823 
824 #ifdef CONF_BOARD_CAN1
825  uint8_t can_rx_message[CONF_MCAN_ELEMENT_DATA_SIZE];
826  uint32_t id;
827  uint8_t lenCAN;
828  is_can_message msg;
829  msg.startByte = CAN_HDR;
830  msg.endByte = CAN_FTR;
831  if((lenCAN = mcan_receive_message(&id, can_rx_message)) > 0)// && --timeout > 0))
832  {
833  msg.address = id;
834  msg.payload = *(is_can_payload*)can_rx_message;
835  msg.dlc = lenCAN;
836  com_bridge_forward(EVB2_PORT_CAN,(uint8_t*)&msg, sizeof(is_can_message));
837  }
838  /*Test CAN*/
839  //static uint8_t tx_message_1[8] = { 0x80, 0x81, 0x82, 0x83, 0x84, 0x85, 0x86, 0x87};
840  //mcan_send_message(0x100000A5, tx_message_1, CONF_MCAN_ELEMENT_DATA_SIZE);
841 #endif
842 }
843 
844 
846 {
847  const size_t xTriggerLevel = 1;
851 
852  for(int i=0; i<COM_RX_PORT_COUNT; i++)
853  {
854  is_comm_init(&(g_comRxPort[i].comm), g_comRxPort[i].comm_buffer, PKT_BUF_SIZE);
855 
856  // Use alternate decode buffer on EVB so we can preserve and forward original packet received.
857  g_comRxPort[i].comm.altDecodeBuf = s_rxDecodeBuffer;
858  }
859 }
StreamBufferHandle_t g_xStreamBufferWiFiTx
uint32_t bits
Definition: data_sets.h:3032
#define _MIN(a, b)
Definition: ISConstants.h:298
d
void uINS_stream_stop_all(is_comm_instance_t &comm)
#define LED_ON(led)
Definition: user_board.h:236
StreamBufferHandle_t g_xStreamBufferWiFiRx
static uint8_t s_rxDecodeBuffer[PKT_BUF_SIZE]
uint32_t options
Definition: data_sets.h:1139
void enable_bootloader(int pHandle)
Definition: bootloaderApp.c:82
uint32_t h3sp330BaudRate
Definition: data_sets.h:3071
uint8_t dlc
uint32_t address
#define DID_EVB_DEBUG_ARRAY
Definition: data_sets.h:116
dev_info_t uInsInfo
Definition: globals.h:43
int serSetBaudRate(int serialNum, int baudrate)
Change USART baudrate. 0 on success, -1 on failure.
Definition: d_usartDMA.c:995
uint32_t cbf[EVB2_PORT_COUNT]
Definition: data_sets.h:3026
#define UNUSED(v)
Marking v as a unused parameter or value.
Definition: compiler.h:86
int comManagerValidateBaudRate(unsigned int baudRate)
Definition: com_manager.c:1573
void com_bridge_smart_forward(uint32_t srcPort, uint32_t ledPin)
static void ioport_set_pin_level(ioport_pin_t pin, bool level)
Set an IOPORT pin to a specified logical value.
Definition: ioport.h:275
#define xStreamBufferCreate(xBufferSizeBytes, xTriggerLevelBytes)
int comWrite(int serialNum, const unsigned char *buf, int size, uint32_t ledPin)
No parity.
#define US_MR_PAR_EVEN
(US_MR) Even parity
uint32_t used
Definition: USBD.h:95
#define US_MR_NBSTOP_1_BIT
(US_MR) 1 stop bit
#define LED_WIFI_RXD_PIN
Definition: user_board.h:285
ins_1_t ins1
Definition: data_sets.h:3406
int xbee_runtime_mode(void)
Definition: xbee.cpp:364
void CAN_init(void)
Definition: CAN.cpp:26
#define UART_XBEE_N_DTR_PIN
Definition: user_board.h:184
uint32_t id
Definition: ISComm.h:375
#define DID_INS_1
Definition: data_sets.h:38
uint32_t radioNID
Definition: data_sets.h:3038
uint32_t size
Definition: ISComm.h:378
uint8_t ssid[WIFI_SSID_PSK_SIZE]
Definition: data_sets.h:2973
void xbee_step(is_comm_instance_t *comm)
Definition: xbee.cpp:246
is_can_payload payload
evb_rtos_info_t g_rtos
Definition: globals.c:27
size_t xStreamBufferReceive(StreamBufferHandle_t xStreamBuffer, void *pvRxData, size_t xBufferLengthBytes, TickType_t xTicksToWait) PRIVILEGED_FUNCTION
#define LE32_TO_CPU(x)
Definition: compiler.h:904
uint64_t bits
Definition: data_sets.h:1301
void xbee_init(void)
Definition: xbee.cpp:236
Odd parity.
bool d_usartDMA_callback_cdc_enable(void)
Definition: d_usartDMA.c:160
bool g_enRtosStats
Definition: globals.c:35
#define PKT_BUF_SIZE
Definition: ISComm.h:98
void com_bridge_forward(uint32_t srcPort, uint8_t *buf, int len)
void board_IO_config(void)
Definition: init.c:393
debug_array_t g_debug
Definition: globals.c:26
#define DID_COUNT
Definition: data_sets.h:138
packet_hdr_t hdr
Definition: ISComm.h:357
#define DID_DEV_INFO
Definition: data_sets.h:35
#define DID_RMC
Definition: data_sets.h:43
#define DID_INS_2
Definition: data_sets.h:39
int is_comm_get_data(is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, uint32_t periodMultiple)
Definition: ISComm.c:588
#define NULL
Definition: nm_bsp.h:52
StreamBufferHandle_t g_xStreamBufferUINS
uint32_t h4xRadioBaudRate
Definition: data_sets.h:3074
int serRead(int serialNum, unsigned char *buf, int size)
Read data on USART. Returns number of bytes read. With use of the PDCA ring buffer, buffer overrun may occur if bytes are received is greater than bytes read plus buffer size.
Definition: d_usartDMA.c:782
#define LED_INS_TXD_PIN
Definition: user_board.h:280
char is_comm_copy_to_struct(void *sptr, const is_comm_instance_t *instance, const unsigned int maxsize)
Definition: ISComm.c:1008
void d_usartDMA_callback_cdc_disable(void)
Definition: d_usartDMA.c:166
#define LED_WIFI_TXD_PIN
Definition: user_board.h:286
#define WIFI_SSID_PSK_SIZE
Definition: data_sets.h:2968
void sendRadio(uint8_t *data, int dataSize, bool sendXbee, bool sendXrad)
uint32_t port
Definition: data_sets.h:2986
int error_check_config(evb_flash_cfg_t *cfg)
Definition: globals.c:396
#define US_MR_PAR_NO
(US_MR) No parity
void communications_init(void)
ins_2_t ins2
Definition: globals.h:44
uint8_t psk[WIFI_SSID_PSK_SIZE]
Definition: data_sets.h:2976
uint32_t flash_write_needed
Definition: globals.h:49
uint32_t timeOfWeekMs
Definition: data_sets.h:2946
uint32_t week
Definition: data_sets.h:2943
uint32_t week
Definition: CAN_comm.h:26
uint8_t startByte
#define CONF_MCAN_ELEMENT_DATA_SIZE
Definition: conf_mcan.h:77
Parity forced to 1 (mark)
comm_rx_port_t g_comRxPort[COM_RX_PORT_COUNT]
uint32_t radioPowerLevel
Definition: data_sets.h:3041
ins_3_t ins3
Definition: data_sets.h:3408
#define LED_XBEE_TXD_PIN
Definition: user_board.h:283
double timeOfWeek
Definition: data_sets.h:417
void com_bridge_apply_preset(evb_flash_cfg_t *cfg)
Definition: globals.c:147
void callback_cdc_set_config(uint8_t port, usb_cdc_line_coding_t *cfg)
#define US_MR_NBSTOP_2_BIT
(US_MR) 2 stop bits
bool LogData(unsigned int device, p_data_hdr_t *dataHdr, const uint8_t *dataBuf)
Definition: ISLogger.cpp:348
is_comm_buffer_t buf
Definition: ISComm.h:488
int spiTouINS_serWrite(const unsigned char *buf, int size)
Definition: spiTouINS.c:393
int is_comm_set_data(is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, void *data)
Definition: ISComm.c:634
void handle_data_from_host(is_comm_instance_t *comm, protocol_type_t ptype)
#define UART_XBEE_N_RTS_PIN
Definition: user_board.h:181
#define STREAM_BUFFER_SIZE
Definition: globals.h:70
#define US_MR_PAR_MARK
(US_MR) Parity forced to 1 (Mark)
int is_comm_free(is_comm_instance_t *instance)
Definition: ISComm.c:462
uint8_t * pktPtr
Definition: ISComm.h:512
evb_status_t g_status
Definition: globals.c:21
uint32_t cbOptions
Definition: data_sets.h:3029
uint32_t ipAddr
Definition: data_sets.h:2983
void refresh_CFG_LED(void)
Definition: init.c:377
#define PID_GET_DATA
Definition: ISComm.h:182
uint8_t cbPreset
Definition: data_sets.h:3020
#define US_MR_CHRL_8_BIT
(US_MR) Character length is 8 bits
#define US_MR_PAR_ODD
(US_MR) Odd parity
uint8_t * start
Definition: ISComm.h:447
uint32_t g_uInsBootloaderEnableTimeMs
Definition: globals.c:34
ins_4_t ins4
Definition: data_sets.h:3409
uint32_t g_comm_time_ms
Definition: globals.c:32
void uINS_stream_enable_PPD(is_comm_instance_t &comm)
uint8_t * tail
Definition: ISComm.h:459
uint8_t endByte
#define DATA_CHUNK_MARKER
Definition: DataChunk.h:23
void wifi_reinit(void)
Definition: wifi.c:252
void callback_cdc_set_dtr(uint8_t port, bool b_enable)
int comRead(int serialNum, unsigned char *buf, int bufSize, uint32_t ledPin)
dev_info_t g_evbDevInfo
Definition: globals.c:19
USBInterfaceDescriptor data
uint8_t * scan
Definition: ISComm.h:462
uint8_t pid
Definition: ISComm.h:322
Even parity.
evb_server_t server[NUM_WIFI_PRESETS]
Definition: data_sets.h:3047
#define DID_EVB_DEV_INFO
Definition: data_sets.h:127
protocol_type_t ptype
#define CAN_FTR
void is_comm_init(is_comm_instance_t *instance, uint8_t *buffer, int bufferSize)
Definition: ISComm.c:185
#define DID_EVB_FLASH_CFG
Definition: data_sets.h:115
void update_flash_cfg(evb_flash_cfg_t &newCfg)
#define DID_EVB_STATUS
Definition: data_sets.h:114
#define EVB_CFG_BITS_IDX_SERVER(bits)
Definition: data_sets.h:3003
uint32_t marker
#define DID_INS_3
Definition: data_sets.h:99
evb_flash_cfg_t * g_flashCfg
Definition: globals.c:22
p_data_hdr_t dataHdr
Definition: ISComm.h:506
void enable_bootloader_assistant(void)
#define LED_INS_RXD_PIN
Definition: user_board.h:279
uint32_t flash_write_enable
Definition: globals.h:51
#define ASCII_MESSAGEID_TO_UINT(c4)
Definition: ISComm.h:241
1.5 stop bits
#define PORT_SEL_USB
bool g_loggerEnabled
Definition: globals.c:33
#define CAN_HDR
size_t xStreamBufferSend(StreamBufferHandle_t xStreamBuffer, const void *pvTxData, size_t xDataLengthBytes, TickType_t xTicksToWait) PRIVILEGED_FUNCTION
uint8_t mcan_receive_message(uint32_t *id_value, uint8_t *data)
Definition: CAN.cpp:78
void step_com_bridge(is_comm_instance_t &comm)
void * StreamBufferHandle_t
Definition: stream_buffer.h:65
protocol_type_t
Definition: ISComm.h:75
uint8_t * altDecodeBuf
Definition: ISComm.h:515
protocol_type_t is_comm_parse(is_comm_instance_t *instance)
Definition: ISComm.c:514
int is_comm_data(is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, void *data)
Definition: ISComm.c:639
packet_t pkt
Definition: ISComm.h:521
Autogenerated API include file for the Atmel Software Framework (ASF)
uint32_t portOptions
Definition: data_sets.h:3068
#define RMC_PRESET_PPD_BITS
Definition: data_sets.h:1282
Parity forced to 0 (space)
nvr_manage_t g_nvr_manage_config
Definition: globals.c:23
int spiTouINS_serRead(unsigned char *buf, int size)
Definition: spiTouINS.c:517
void log_ublox_raw_to_SD(cISLogger &logger, uint8_t *dataPtr, uint32_t dataSize)
#define US_MR_PAR_SPACE
(US_MR) Parity forced to 0 (Space)
#define COM_RX_PORT_COUNT
uint32_t offset
Definition: ISComm.h:381
void handle_data_from_uINS(p_data_hdr_t &dataHdr, uint8_t *data)
int is_comm_stop_broadcasts_current_port(is_comm_instance_t *instance)
Definition: ISComm.c:654
#define MAX_DATASET_SIZE
Definition: ISComm.h:91
uint32_t radioPID
Definition: data_sets.h:3035
uint8_t uinsComPort
Definition: data_sets.h:3059
evb_msg_t g_msg
Definition: globals.c:25
#define DID_INS_4
Definition: data_sets.h:100
int serRxUsed(int serialNum)
Returns number of bytes used in Rx buffer.
Definition: d_usartDMA.c:301
uint32_t can_receive_address
Definition: data_sets.h:3056
Line Coding structure.
#define EVB_CFG_BITS_IDX_WIFI(bits)
Definition: data_sets.h:3002
uint32_t size
evb_wifi_t wifi[NUM_WIFI_PRESETS]
Definition: data_sets.h:3044
#define US_MR_NBSTOP_1_5_BIT
(US_MR) 1.5 stop bit (SYNC = 0) or reserved (SYNC = 1)
void log_uINS_data(cISLogger &logger, is_comm_instance_t &comm)
void uINS_stream_enable_std(is_comm_instance_t &comm)
char copyDataPToStructP2(void *sptr, const p_data_hdr_t *dataHdr, const uint8_t *dataBuf, const unsigned int maxsize)
Definition: ISComm.c:989
uint32_t h8gpioBaudRate
Definition: data_sets.h:3077
uint32_t CANbaud_kbps
Definition: data_sets.h:3053
#define DID_EVB_RTOS_INFO
Definition: data_sets.h:117
void com_bridge_smart_forward_xstream(uint32_t srcPort, StreamBufferHandle_t xStreamBuffer)
is_comm_instance_t comm
int serWrite(int serialNum, const unsigned char *buf, int size)
Write data on USART. Returns number of bytes written.
Definition: d_usartDMA.c:443
uint8_t * dataPtr
Definition: ISComm.h:509


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