ISComm.h
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2021 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 #ifndef IS_SIMPLE_INTERFACE_H
14 #define IS_SIMPLE_INTERFACE_H
15 
16 #include "data_sets.h"
17 #include "stddef.h"
18 
19 #ifdef __cplusplus
20 extern "C" {
21 #endif
22 
37 // -------------------------------------------------------------------------------------------------------------------------------
38 // Inertial Sense simple communications interface --------------------------------------------------------------------------------
39 // -------------------------------------------------------------------------------------------------------------------------------
40 // The simple comm interface does not require any of the com manager APIs and is designed for simple or lightweight scenarios, tiny embedded platforms, etc.
41 // *****************************************************************************
42 // ****** Binary messages ******
43 // *****************************************************************************
44 
46 #define _DID_INS_ECEF_QE2B DID_INS_4
47 #define _DID_INS_LLA_EULER_NED DID_INS_1
48 #define _DID_INS_LLA_QN2B DID_INS_3
51 #define _DID_IMU_DUAL DID_DUAL_IMU
52 #define _DID_IMU_PREINTEGRATED_IMU DID_PREINTEGRATED_IMU
55 #define _DID_GPS1_POS DID_GPS1_POS
58 #define _DID_MAG_CAL DID_MAG_CAL
59 #define _DID_MAGNETOMETER_1 DID_MAGNETOMETER_1
60 #define _DID_MAGNETOMETER_2 DID_MAGNETOMETER_2
61 #define _DID_BAROMETER DID_BAROMETER
62 #define _DID_WHEEL_ENCODER DID_WHEEL_ENCODER
63 #define _DID_POS_MEASUREMENT DID_POSITION_MEASUREMENT
66 #define _DID_DEV_INFO DID_DEV_INFO
67 #define _DID_BIT DID_BIT
68 #define _DID_STROBE_IN_TIME DID_STROBE_IN_TIME
71 #define _DID_FLASH_CONFIG DID_FLASH_CONFIG
72 #define _DID_RMC DID_RMC
75 typedef enum
76 {
78  _PTYPE_PARSE_ERROR = 0xFFFFFFFF,
82  _PTYPE_ASCII_NMEA = 0xBFFFFFFF,
83  _PTYPE_UBLOX = 0xAFFFFFFF,
84  _PTYPE_RTCM3 = 0x9FFFFFFF,
86 
88 #define IS_COM_BAUDRATE_DEFAULT IS_BAUDRATE_921600
89 
91 #define MAX_DATASET_SIZE 1024
92 
94 #define PKT_OVERHEAD_SIZE 8 // = START_BYTE + INFO_BYTE + COUNTER_BYTE + FLAGS_BYTE + CHECKSUM_BYTE_1 + CHECKSUM_BYTE_2 + CHECKSUM_BYTE_3 + END_BYTE
95 
97 #ifndef PKT_BUF_SIZE
98 #define PKT_BUF_SIZE 2048
99 #endif
100 
102 #define MAX_PKT_OVERHEAD_SIZE (PKT_OVERHEAD_SIZE + PKT_OVERHEAD_SIZE - 2) // worst case for packet encoding header / footer
103 
105 #define MAX_PKT_BODY_SIZE (((PKT_BUF_SIZE - MAX_PKT_OVERHEAD_SIZE) / 2) & 0xFFFFFFFE) // worst case for packet encoding body, rounded down to even number
106 
108 #define MAX_P_DATA_BODY_SIZE (MAX_PKT_BODY_SIZE-sizeof(p_data_hdr_t)) // Data size limit
109 
111 #define MAX_P_ACK_BODY_SIZE (MAX_PKT_BODY_SIZE-sizeof(p_ack_hdr_t)) // Ack data size
112 
114 #define CHECKSUM_SEED 0x00AAAAAA
115 
118 // Major (in com_manager.h)
119 #define PROTOCOL_VERSION_CHAR0 (1)
120 
121 // version 1: initial release
122 // version 2: 24 bit checksum support
123 #define PROTOCOL_VERSION_CHAR1 (2)
124 
125 // Minor (in data_sets.h)
126 // #define PROTOCOL_VERSION_CHAR2 0
127 // #define PROTOCOL_VERSION_CHAR3 0
128 
129 #define UBLOX_HEADER_SIZE 6
130 #define RTCM3_HEADER_SIZE 3
131 
134 
136 typedef enum
137 {
147 
149 } baud_rate_t;
150 
152 extern const unsigned int g_validBaudRates[IS_BAUDRATE_COUNT];
153 
154 /*
155 Packet Overview
156 
157 Byte
158 0 Packet start byte
159 1 Packet indo: ID (mask 0x1F) | reserved bits (mask 0xE)
160 2 Packet counter (for ACK and retry)
161 3 Packet flags
162 
163 // packet body, may or may not exist depending on packet id - packet body is made up of 4 byte or 8 byte values.
164 4-7 Data identifier
165 8-11 Data length
166 12-15 Data offset
167 16-19 Data start
168 (n-8)-(n-5) Last piece of data
169 // end data
170 
171 n-4 Reserved
172 n-3 Checksum high byte
173 n-2 Checksum low byte
174 n-1 Packet end byte
175 */
176 
177 // Packet IDs
178 typedef uint32_t ePacketIDs;
179 
180 #define PID_INVALID (ePacketIDs)0
181 #define PID_ACK (ePacketIDs)1
182 #define PID_NACK (ePacketIDs)2
183 #define PID_GET_DATA (ePacketIDs)3
184 #define PID_DATA (ePacketIDs)4
185 #define PID_SET_DATA (ePacketIDs)5
186 #define PID_STOP_BROADCASTS_ALL_PORTS (ePacketIDs)6
187 #define PID_STOP_DID_BROADCAST (ePacketIDs)7
188 #define PID_STOP_BROADCASTS_CURRENT_PORT (ePacketIDs)8
189 #define PID_COUNT (ePacketIDs)9
190 #define PID_MAX_COUNT (ePacketIDs)32
193 typedef struct
194 {
196  uint32_t size;
197 
199  uint8_t buf[PKT_BUF_SIZE];
200 } buffer_t;
201 
203 typedef struct
204 {
206  uint8_t *ptr;
207 
209  uint32_t size;
210 } bufPtr_t;
211 
213 typedef struct
214 {
216  uint8_t *txPtr;
217 
219  uint8_t *rxPtr;
220 
222  uint32_t size;
223 } bufTxRxPtr_t;
224 
226 typedef enum
227 {
230 
233 
236 
239 } asciiDataType;
240 
242 #define ASCII_MESSAGEID_TO_UINT(c4) ((uint32_t)(c4)[0] << 24 | ((uint32_t)(c4)[1] << 16) | ((uint32_t)(c4)[2] << 8) | ((uint32_t)(c4)[3]))
243 
245 {
246  // bit set for little endian, bit cleared for big endian
249 
250  // has any valid packet been received
252 
253  // multi-packet data set
255 
256  // Allow for arbitrary length in bytes of data, not necessarily multiple of 4. Don't auto-swap bytes for endianness
258 
259  // Checksum is the new 24 bit algorithm instead of the old 16 bit algorithm
261 };
262 
271 {
274 
277 
280 
282  PSC_END_BYTE = 0xFE,
283 
286 
289 
292 
295 };
296 
298 typedef struct
299 {
301  unsigned char messageId[4];
302 
304  uint8_t* ptr;
305 
307  int ptrSize;
308 
311 
313  uint16_t* fieldsAndOffsets;
315 
317 typedef struct
318 {
320  uint8_t startByte;
321 
323  uint8_t pid;
324 
326  uint8_t counter;
327 
335  uint8_t flags;
336 } packet_hdr_t;
337 
339 typedef struct
340 {
342  uint8_t cksum3;
343 
345  uint8_t cksum2;
346 
348  uint8_t cksum1;
349 
351  uint8_t stopByte;
352 } packet_ftr_t;
353 
355 typedef struct
356 {
359 
362 } packet_t;
363 
365 typedef struct
366 {
367  packet_hdr_t hdr; // Packet header
368  bufPtr_t bodyHdr; // Body header
369  bufPtr_t txData; // Pointer and size of data to send
370 } pkt_info_t;
371 
373 typedef struct
374 {
376  uint32_t id;
377 
379  uint32_t size;
380 
382  uint32_t offset;
383 } p_data_hdr_t;
384 
386 typedef struct
387 {
390 
392  uint8_t buf[MAX_DATASET_SIZE];
394 
396 typedef struct
397 {
399  uint32_t id;
400 
402  uint32_t size;
403 
405  uint32_t offset;
406 
412 } p_data_get_t;
413 
415 typedef struct
416 {
418  uint32_t id;
420 
422 typedef struct
423 {
425  uint32_t pktInfo;
426 
428  uint32_t pktCounter;
429 } p_ack_hdr_t;
430 
432 typedef struct
433 {
436 
438  union
439  {
440  uint8_t buf[sizeof(p_data_hdr_t)];
442  } body;
443 } p_ack_t, p_nack_t;
444 
445 typedef struct
446 {
448  uint8_t* start;
449 
451  uint8_t* end;
452 
454  uint32_t size;
455 
457  uint8_t* head;
458 
460  uint8_t* tail;
461 
463  uint8_t* scan;
464 
466 
467 typedef struct
468 {
470  uint8_t enableISB;
471 
473  uint8_t enableASCII;
474 
476  uint8_t enableUblox;
477 
479  uint8_t enableRTCM3;
481 
483 typedef struct
484 {
490 
493 
495  uint32_t txPktCount;
496 
498  uint32_t rxErrorCount;
499 
501  uint32_t hasStartByte;
502 
504  int32_t parseState;
505 
508 
510  uint8_t* dataPtr;
511 
513  uint8_t* pktPtr;
514 
516  uint8_t* altDecodeBuf;
517 
519  uint32_t ackNeeded;
520 
523 
525 
527 POP_PACK
528 
533 void is_comm_init(is_comm_instance_t* instance, uint8_t *buffer, int bufferSize);
534 
567 protocol_type_t is_comm_parse_byte(is_comm_instance_t* instance, uint8_t byte);
568 
608 
614 int is_comm_free(is_comm_instance_t* instance);
615 
626 int is_comm_get_data(is_comm_instance_t* instance, uint32_t dataId, uint32_t offset, uint32_t size, uint32_t periodMultiple);
627 
635 int is_comm_get_data_rmc(is_comm_instance_t* instance, uint64_t rmcBits);
636 
647 int is_comm_set_data(is_comm_instance_t* instance, uint32_t dataId, uint32_t offset, uint32_t size, void* data);
648 
652 int is_comm_data(is_comm_instance_t* instance, uint32_t dataId, uint32_t offset, uint32_t size, void* data);
653 
660 
667 
668 
669 // -------------------------------------------------------------------------------------------------------------------------------
670 // Common packet encode / decode functions
671 // -------------------------------------------------------------------------------------------------------------------------------
672 // common encode / decode for com manager and simple interface
673 int is_encode_binary_packet(void* srcBuffer, unsigned int srcBufferLength, packet_hdr_t* hdr, uint8_t additionalPktFlags, void* encodedPacket, int encodedPacketLength);
674 int is_decode_binary_packet(packet_t *pkt, unsigned char* pbuf, int pbufSize);
675 int is_decode_binary_packet_byte(uint8_t** _ptrSrc, uint8_t** _ptrDest, uint32_t* checksum, uint32_t shift);
676 void is_decode_binary_packet_footer(packet_ftr_t* ftr, uint8_t* ptrSrc, uint8_t** ptrSrcEnd, uint32_t* checksum);
677 void is_enable_packet_encoding(int enabled); // default is enabled
678 
679 unsigned int calculate24BitCRCQ(unsigned char* buffer, unsigned int len);
680 unsigned int getBitsAsUInt32(const unsigned char* buffer, unsigned int pos, unsigned int len);
681 
683 char copyDataPToStructP(void *sptr, const p_data_t *data, const unsigned int maxsize);
684 
686 char copyDataPToStructP2(void *sptr, const p_data_hdr_t *dataHdr, const uint8_t *dataBuf, const unsigned int maxsize);
687 
689 char is_comm_copy_to_struct(void *sptr, const is_comm_instance_t *com, const unsigned int maxsize);
690 
691 #ifdef __cplusplus
692 }
693 #endif
694 
695 #endif // IS_SIMPLE_INTERFACE_H
uint8_t enableISB
Definition: ISComm.h:470
char copyDataPToStructP2(void *sptr, const p_data_hdr_t *dataHdr, const uint8_t *dataBuf, const unsigned int maxsize)
Definition: ISComm.c:989
bufPtr_t body
Definition: ISComm.h:361
int is_comm_stop_broadcasts_current_port(is_comm_instance_t *instance)
Definition: ISComm.c:654
packet_hdr_t hdr
Definition: ISComm.h:367
uint8_t startByte
Definition: ISComm.h:320
uint8_t * txPtr
Definition: ISComm.h:216
void is_enable_packet_encoding(int enabled)
Definition: ISComm.c:1002
unsigned int calculate24BitCRCQ(unsigned char *buffer, unsigned int len)
Definition: ISComm.c:21
uint8_t * ptr
Definition: ISComm.h:304
uint8_t * end
Definition: ISComm.h:451
asciiDataType
Definition: ISComm.h:226
uint32_t id
Definition: ISComm.h:376
uint32_t size
Definition: ISComm.h:379
is_comm_config_t config
Definition: ISComm.h:492
uint8_t enableASCII
Definition: ISComm.h:473
int is_comm_free(is_comm_instance_t *instance)
Definition: ISComm.c:462
uint8_t cksum1
Definition: ISComm.h:348
uint32_t size
Definition: ISComm.h:209
int is_comm_stop_broadcasts_all_ports(is_comm_instance_t *instance)
Definition: ISComm.c:644
int is_decode_binary_packet(packet_t *pkt, unsigned char *pbuf, int pbufSize)
Definition: ISComm.c:900
uint8_t enableRTCM3
Definition: ISComm.h:479
uint8_t enableUblox
Definition: ISComm.h:476
#define PKT_BUF_SIZE
Definition: ISComm.h:98
int32_t parseState
Definition: ISComm.h:504
packet_hdr_t hdr
Definition: ISComm.h:358
#define PUSH_PACK_1
Definition: ISConstants.h:231
bufPtr_t bodyHdr
Definition: ISComm.h:368
uint32_t pktInfo
Definition: ISComm.h:425
bufPtr_t txData
Definition: ISComm.h:369
unsigned int getBitsAsUInt32(const unsigned char *buffer, unsigned int pos, unsigned int len)
Definition: ISComm.c:74
uint8_t stopByte
Definition: ISComm.h:351
uint32_t offset
Definition: ISComm.h:405
char is_comm_copy_to_struct(void *sptr, const is_comm_instance_t *com, const unsigned int maxsize)
Definition: ISComm.c:1008
int is_comm_data(is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, void *data)
Definition: ISComm.c:639
uint32_t pktCounter
Definition: ISComm.h:428
p_ack_hdr_t hdr
Definition: ISComm.h:435
protocol_type_t is_comm_parse_byte(is_comm_instance_t *instance, uint8_t byte)
Definition: ISComm.c:499
p_data_hdr_t dataHdr
Definition: ISComm.h:441
is_comm_buffer_t buf
Definition: ISComm.h:489
uint32_t size
Definition: ISComm.h:454
POP_PACK void is_comm_init(is_comm_instance_t *instance, uint8_t *buffer, int bufferSize)
Definition: ISComm.c:185
int is_comm_get_data_rmc(is_comm_instance_t *instance, uint64_t rmcBits)
Definition: ISComm.c:605
ePktHdrFlags
Definition: ISComm.h:244
uint32_t size
Definition: ISComm.h:222
uint8_t * pktPtr
Definition: ISComm.h:513
const unsigned int g_validBaudRates[IS_BAUDRATE_COUNT]
Definition: ISComm.c:84
uint8_t cksum2
Definition: ISComm.h:345
ePktSpecialChars
Definition: ISComm.h:270
uint32_t id
Definition: ISComm.h:418
uint8_t * rxPtr
Definition: ISComm.h:219
uint8_t * start
Definition: ISComm.h:448
struct p_data_t p_data_set_t
uint32_t hasStartByte
Definition: ISComm.h:501
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
int is_encode_binary_packet(void *srcBuffer, unsigned int srcBufferLength, packet_hdr_t *hdr, uint8_t additionalPktFlags, void *encodedPacket, int encodedPacketLength)
Definition: ISComm.c:791
char copyDataPToStructP(void *sptr, const p_data_t *data, const unsigned int maxsize)
Definition: ISComm.c:975
p_data_hdr_t hdr
Definition: ISComm.h:389
uint32_t ackNeeded
Definition: ISComm.h:519
uint32_t rxErrorCount
Definition: ISComm.h:498
uint8_t * tail
Definition: ISComm.h:460
uint16_t * fieldsAndOffsets
Definition: ISComm.h:313
uint32_t id
Definition: ISComm.h:399
USBInterfaceDescriptor data
uint8_t * scan
Definition: ISComm.h:463
uint8_t pid
Definition: ISComm.h:323
int is_decode_binary_packet_byte(uint8_t **_ptrSrc, uint8_t **_ptrDest, uint32_t *checksum, uint32_t shift)
Definition: ISComm.c:761
baud_rate_t
Definition: ISComm.h:136
uint32_t size
Definition: ISComm.h:196
uint32_t ePacketIDs
Definition: ISComm.h:178
struct p_ack_t p_nack_t
void is_decode_binary_packet_footer(packet_ftr_t *ftr, uint8_t *ptrSrc, uint8_t **ptrSrcEnd, uint32_t *checksum)
Definition: ISComm.c:704
uint32_t txPktCount
Definition: ISComm.h:495
p_data_hdr_t dataHdr
Definition: ISComm.h:507
uint8_t cksum3
Definition: ISComm.h:342
#define POP_PACK
Definition: ISConstants.h:234
uint8_t * head
Definition: ISComm.h:457
protocol_type_t
Definition: ISComm.h:75
uint8_t * ptr
Definition: ISComm.h:206
uint8_t * altDecodeBuf
Definition: ISComm.h:516
packet_t pkt
Definition: ISComm.h:522
uint8_t flags
Definition: ISComm.h:335
protocol_type_t is_comm_parse(is_comm_instance_t *instance)
Definition: ISComm.c:514
uint32_t bc_period_multiple
Definition: ISComm.h:411
uint32_t offset
Definition: ISComm.h:382
#define MAX_DATASET_SIZE
Definition: ISComm.h:91
uint8_t counter
Definition: ISComm.h:326
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
uint32_t size
Definition: ISComm.h:402
uint8_t * dataPtr
Definition: ISComm.h:510


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:57