#include "ISComm.h"
Go to the source code of this file.
Macros | |
| #define | FOUND_START_BYTE(init) if(init){ instance->hasStartByte = byte; instance->buf.head = instance->buf.scan-1; } |
| #define | START_BYTE_SEARCH_ERROR() |
Functions | |
| unsigned int | calculate24BitCRCQ (unsigned char *buffer, unsigned int len) |
| char | copyDataPToStructP (void *sptr, const p_data_t *data, const unsigned int maxsize) |
| char | copyDataPToStructP2 (void *sptr, const p_data_hdr_t *dataHdr, const uint8_t *dataBuf, const unsigned int maxsize) |
| static int | dataIdShouldSwap (uint32_t dataId) |
| static uint8_t * | encodeByteAddToBuffer (uint32_t val, uint8_t *ptrDest) |
| unsigned int | getBitsAsUInt32 (const unsigned char *buffer, unsigned int pos, unsigned int len) |
| char | is_comm_copy_to_struct (void *sptr, const is_comm_instance_t *instance, const unsigned int maxsize) |
| int | is_comm_data (is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, void *data) |
| int | is_comm_free (is_comm_instance_t *instance) |
| int | is_comm_get_data (is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, uint32_t periodMultiple) |
| int | is_comm_get_data_rmc (is_comm_instance_t *instance, uint64_t rmcBits) |
| void | is_comm_init (is_comm_instance_t *instance, uint8_t *buffer, int bufferSize) |
| protocol_type_t | is_comm_parse (is_comm_instance_t *instance) |
| protocol_type_t | is_comm_parse_byte (is_comm_instance_t *instance, uint8_t byte) |
| int | is_comm_set_data (is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, void *data) |
| int | is_comm_stop_broadcasts_all_ports (is_comm_instance_t *instance) |
| int | is_comm_stop_broadcasts_current_port (is_comm_instance_t *instance) |
| int | is_decode_binary_packet (packet_t *pkt, unsigned char *pbuf, int pbufSize) |
| int | is_decode_binary_packet_byte (uint8_t **_ptrSrc, uint8_t **_ptrDest, uint32_t *checksum, uint32_t shift) |
| void | is_decode_binary_packet_footer (packet_ftr_t *ftr, uint8_t *ptrSrc, uint8_t **ptrSrcEnd, uint32_t *checksum) |
| void | is_enable_packet_encoding (int enabled) |
| int | is_encode_binary_packet (void *srcBuffer, unsigned int srcBufferLength, packet_hdr_t *hdr, uint8_t additionalPktFlags, void *encodedPacket, int encodedPacketLength) |
| static protocol_type_t | processAsciiPkt (is_comm_instance_t *instance) |
| static protocol_type_t | processInertialSensePkt (is_comm_instance_t *instance) |
| static protocol_type_t | processRtcm3Byte (is_comm_instance_t *instance) |
| static protocol_type_t | processUbloxByte (is_comm_instance_t *instance) |
| static __inline void | reset_parser (is_comm_instance_t *instance) |
| static int | sendData (is_comm_instance_t *instance, uint32_t dataId, uint32_t offset, uint32_t size, void *data, uint32_t pid) |
| static void | swapPacket (packet_t *pkt) |
Variables | |
| const unsigned int | g_validBaudRates [IS_BAUDRATE_COUNT] = { IS_BAUDRATE_3000000, IS_BAUDRATE_921600, IS_BAUDRATE_460800, IS_BAUDRATE_230400, IS_BAUDRATE_115200, IS_BAUDRATE_57600, IS_BAUDRATE_38400, IS_BAUDRATE_19200, IS_BAUDRATE_9600 } |
| static int | s_packetEncodingEnabled = 1 |
| unsigned int calculate24BitCRCQ | ( | unsigned char * | buffer, |
| unsigned int | len | ||
| ) |
| char copyDataPToStructP | ( | void * | sptr, |
| const p_data_t * | data, | ||
| const unsigned int | maxsize | ||
| ) |
| char copyDataPToStructP2 | ( | void * | sptr, |
| const p_data_hdr_t * | dataHdr, | ||
| const uint8_t * | dataBuf, | ||
| const unsigned int | maxsize | ||
| ) |
|
static |
| unsigned int getBitsAsUInt32 | ( | const unsigned char * | buffer, |
| unsigned int | pos, | ||
| unsigned int | len | ||
| ) |
Retrieve the 32 bit unsigned integer value of the specified bits - note that no bounds checking is done on buffer
| buffer | the buffer containing the bits |
| pos | the start bit position in buffer to read at |
| len | the number of bits to read |
| char is_comm_copy_to_struct | ( | void * | sptr, |
| const is_comm_instance_t * | instance, | ||
| const unsigned int | maxsize | ||
| ) |
| int is_comm_data | ( | is_comm_instance_t * | instance, |
| uint32_t | dataId, | ||
| uint32_t | offset, | ||
| uint32_t | size, | ||
| void * | data | ||
| ) |
Same as is_comm_set_data() except NO acknowledge packet is sent in response to this packet.
| int is_comm_free | ( | is_comm_instance_t * | instance | ) |
Removed old data and shift unparsed data to the the buffer start if running out of space at the buffer end. Returns number of bytes available in the bufer.
| instance | the comm instance passed to is_comm_init |
| int is_comm_get_data | ( | is_comm_instance_t * | instance, |
| uint32_t | dataId, | ||
| uint32_t | offset, | ||
| uint32_t | size, | ||
| uint32_t | periodMultiple | ||
| ) |
Encode a binary packet to get data from the device - puts the data ready to send into the buffer passed into is_comm_init
| instance | the comm instance passed to is_comm_init |
| dataId | the data id to request (see DID_* at top of this file) |
| offset | the offset into data to request. Set offset and length to 0 for entire data structure. |
| length | the length into data from offset to request. Set offset and length to 0 for entire data structure. |
| periodMultiple | how often you want the data to stream out, 0 for a one time message and turn off. |
| int is_comm_get_data_rmc | ( | is_comm_instance_t * | instance, |
| uint64_t | rmcBits | ||
| ) |
Encode a binary packet to get predefined list of data sets from the device - puts the data ready to send into the buffer passed into is_comm_init
| instance | the comm instance passed to is_comm_init |
| RMC | bits specifying data messages to stream. See presets: RMC_PRESET_PPD_BITS = post processing data, RMC_PRESET_INS_BITS = INS2 and GPS data at full rate |
| void is_comm_init | ( | is_comm_instance_t * | instance, |
| uint8_t * | buffer, | ||
| int | bufferSize | ||
| ) |
Pop off the packing argument, we can safely allow packing and shifting in memory at this point Init simple communications interface - call this before doing anything else
| instance | communications instance, please ensure that you have set the buffer and bufferSize |
| protocol_type_t is_comm_parse | ( | is_comm_instance_t * | instance | ) |
Decode packet data - when data is available, return value will be the protocol type (see protocol_type_t) and the comm instance dataPtr will point to the start of the valid data. For Inertial Sense binary protocol, comm instance dataHdr contains the data ID (DID), size, and offset.
| instance | the comm instance passed to is_comm_init |
Read a set of bytes (fast method) protocol_type_t ptype;
Get available size of comm buffer int n = is_comm_free(comm);
Read data directly into comm buffer if ((n = mySerialPortRead(comm->buf.tail, n))) { Update comm buffer tail pointer comm->buf.tail += n;
Search comm buffer for valid packets while ((ptype = is_comm_parse(comm)) != _PTYPE_NONE) { switch (ptype) { case _PTYPE_INERTIAL_SENSE_DATA: case _PTYPE_INERTIAL_SENSE_CMD: case _PTYPE_INERTIAL_SENSE_ACK: break; case _PTYPE_UBLOX: break; case _PTYPE_RTCM3: break; case _PTYPE_ASCII_NMEA: break; } } }
| protocol_type_t is_comm_parse_byte | ( | is_comm_instance_t * | instance, |
| uint8_t | byte | ||
| ) |
Decode packet data - when data is available, return value will be the protocol type (see protocol_type_t) and the comm instance dataPtr will point to the start of the valid data. For Inertial Sense binary protocol, comm instance dataHdr contains the data ID (DID), size, and offset.
| instance | the comm instance passed to is_comm_init |
| byte | the byte to decode |
Read one byte (simple method) uint8_t c; protocol_type_t ptype; Read from serial buffer until empty while (mySerialPortRead(&c, 1)) { if ((ptype = is_comm_parse_byte(comm, c)) != _PTYPE_NONE) { switch (ptype) { case _PTYPE_INERTIAL_SENSE_DATA: case _PTYPE_INERTIAL_SENSE_CMD: case _PTYPE_INERTIAL_SENSE_ACK: break; case _PTYPE_UBLOX: break; case _PTYPE_RTCM3: break; case _PTYPE_ASCII_NMEA: break; } } }
| int is_comm_set_data | ( | is_comm_instance_t * | instance, |
| uint32_t | dataId, | ||
| uint32_t | offset, | ||
| uint32_t | size, | ||
| void * | data | ||
| ) |
Encode a binary packet to set data on the device - puts the data ready to send into the buffer passed into is_comm_init. An acknowledge packet is sent in response to this packet.
| instance | the comm instance passed to is_comm_init |
| dataId | the data id to set on the device (see DID_* at top of this file) |
| offset | the offset to start setting data at on the data structure on the device |
| size | the number of bytes to set on the data structure on the device |
| data | the actual data to change on the data structure on the device - this should have at least size bytes available |
| int is_comm_stop_broadcasts_all_ports | ( | is_comm_instance_t * | instance | ) |
Encode a binary packet to stop all messages being broadcast on the device on all ports - puts the data ready to send into the buffer passed into is_comm_init
| instance | the comm instance passed to is_comm_init |
| int is_comm_stop_broadcasts_current_port | ( | is_comm_instance_t * | instance | ) |
Encode a binary packet to stop all messages being broadcast on the device on this port - puts the data ready to send into the buffer passed into is_comm_init
| instance | the comm instance passed to is_comm_init |
| int is_decode_binary_packet | ( | packet_t * | pkt, |
| unsigned char * | pbuf, | ||
| int | pbufSize | ||
| ) |
| int is_decode_binary_packet_byte | ( | uint8_t ** | _ptrSrc, |
| uint8_t ** | _ptrDest, | ||
| uint32_t * | checksum, | ||
| uint32_t | shift | ||
| ) |
| void is_decode_binary_packet_footer | ( | packet_ftr_t * | ftr, |
| uint8_t * | ptrSrc, | ||
| uint8_t ** | ptrSrcEnd, | ||
| uint32_t * | checksum | ||
| ) |
| int is_encode_binary_packet | ( | void * | srcBuffer, |
| unsigned int | srcBufferLength, | ||
| packet_hdr_t * | hdr, | ||
| uint8_t | additionalPktFlags, | ||
| void * | encodedPacket, | ||
| int | encodedPacketLength | ||
| ) |
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
| const unsigned int g_validBaudRates[IS_BAUDRATE_COUNT] = { IS_BAUDRATE_3000000, IS_BAUDRATE_921600, IS_BAUDRATE_460800, IS_BAUDRATE_230400, IS_BAUDRATE_115200, IS_BAUDRATE_57600, IS_BAUDRATE_38400, IS_BAUDRATE_19200, IS_BAUDRATE_9600 } |