Macros | Functions | Variables
ISComm.c File Reference
#include "ISComm.h"
Include dependency graph for ISComm.c:

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
 

Macro Definition Documentation

◆ FOUND_START_BYTE

#define FOUND_START_BYTE (   init)    if(init){ instance->hasStartByte = byte; instance->buf.head = instance->buf.scan-1; }

Definition at line 511 of file ISComm.c.

◆ START_BYTE_SEARCH_ERROR

#define START_BYTE_SEARCH_ERROR ( )

Definition at line 512 of file ISComm.c.

Function Documentation

◆ calculate24BitCRCQ()

unsigned int calculate24BitCRCQ ( unsigned char *  buffer,
unsigned int  len 
)

Calculate 24 bit crc used in formats like RTCM3 - note that no bounds checking is done on buffer

Parameters
bufferthe buffer to calculate the CRC for
lenthe number of bytes to calculate the CRC for
Returns
the CRC value

Definition at line 21 of file ISComm.c.

◆ copyDataPToStructP()

char copyDataPToStructP ( void *  sptr,
const p_data_t data,
const unsigned int  maxsize 
)

Copies packet data into a data structure. Returns 0 on success, -1 on failure.

Definition at line 975 of file ISComm.c.

◆ copyDataPToStructP2()

char copyDataPToStructP2 ( void *  sptr,
const p_data_hdr_t dataHdr,
const uint8_t *  dataBuf,
const unsigned int  maxsize 
)

Copies packet data into a data structure. Returns 0 on success, -1 on failure.

Definition at line 989 of file ISComm.c.

◆ dataIdShouldSwap()

static int dataIdShouldSwap ( uint32_t  dataId)
static

Definition at line 117 of file ISComm.c.

◆ encodeByteAddToBuffer()

static uint8_t* encodeByteAddToBuffer ( uint32_t  val,
uint8_t *  ptrDest 
)
static

Definition at line 88 of file ISComm.c.

◆ getBitsAsUInt32()

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

Parameters
bufferthe buffer containing the bits
posthe start bit position in buffer to read at
lenthe number of bits to read
Returns
the 32 bit unsigned integer value

Definition at line 74 of file ISComm.c.

◆ is_comm_copy_to_struct()

char is_comm_copy_to_struct ( void *  sptr,
const is_comm_instance_t instance,
const unsigned int  maxsize 
)

Copies packet data into a data structure. Returns 0 on success, -1 on failure.

Definition at line 1008 of file ISComm.c.

◆ is_comm_data()

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.

Definition at line 639 of file ISComm.c.

◆ is_comm_free()

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.

Parameters
instancethe comm instance passed to is_comm_init
Returns
the number of bytes available in the comm buffer

Definition at line 462 of file ISComm.c.

◆ is_comm_get_data()

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

Parameters
instancethe comm instance passed to is_comm_init
dataIdthe data id to request (see DID_* at top of this file)
offsetthe offset into data to request. Set offset and length to 0 for entire data structure.
lengththe length into data from offset to request. Set offset and length to 0 for entire data structure.
periodMultiplehow often you want the data to stream out, 0 for a one time message and turn off.
Returns
the number of bytes written to the comm buffer (from is_comm_init), will be less than 1 if error
Remarks
pass an offset and length of 0 to request the entire data structure

Definition at line 588 of file ISComm.c.

◆ is_comm_get_data_rmc()

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

Parameters
instancethe comm instance passed to is_comm_init
RMCbits 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
Returns
the number of bytes written to the comm buffer (from is_comm_init), will be less than 1 if error
Remarks
pass an offset and length of 0 to request the entire data structure

Definition at line 605 of file ISComm.c.

◆ is_comm_init()

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

Parameters
instancecommunications instance, please ensure that you have set the buffer and bufferSize

Definition at line 185 of file ISComm.c.

◆ is_comm_parse()

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.

Parameters
instancethe comm instance passed to is_comm_init
Returns
protocol type when complete valid data is found, otherwise _PTYPE_NONE (0) (see protocol_type_t)
Remarks
when data is available, you can cast the comm instance dataPtr into the appropriate data structure pointer (see binary messages above and data_sets.h) For example usage, see comManagerStepRxInstance() in com_manager.c.

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; } } }

Definition at line 514 of file ISComm.c.

◆ is_comm_parse_byte()

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.

Parameters
instancethe comm instance passed to is_comm_init
bytethe byte to decode
Returns
protocol type when complete valid data is found, otherwise _PTYPE_NONE (0) (see protocol_type_t)
Remarks
when data is available, you can cast the comm instance dataPtr into the appropriate data structure pointer (see binary messages above and data_sets.h) For example usage, see comManagerStepRxInstance() in com_manager.c.

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; } } }

Definition at line 499 of file ISComm.c.

◆ is_comm_set_data()

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.

Parameters
instancethe comm instance passed to is_comm_init
dataIdthe data id to set on the device (see DID_* at top of this file)
offsetthe offset to start setting data at on the data structure on the device
sizethe number of bytes to set on the data structure on the device
datathe actual data to change on the data structure on the device - this should have at least size bytes available
Returns
the number of bytes written to the comm buffer (from is_comm_init), will be less than 1 if error
Remarks
pass an offset and length of 0 to set the entire data structure, in which case data needs to have the full number of bytes available for the appropriate struct matching the dataId parameter.

Definition at line 634 of file ISComm.c.

◆ is_comm_stop_broadcasts_all_ports()

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

Parameters
instancethe comm instance passed to is_comm_init
Returns
0 if success, otherwise an error code

Definition at line 644 of file ISComm.c.

◆ is_comm_stop_broadcasts_current_port()

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

Parameters
instancethe comm instance passed to is_comm_init
Returns
0 if success, otherwise an error code

Definition at line 654 of file ISComm.c.

◆ is_decode_binary_packet()

int is_decode_binary_packet ( packet_t pkt,
unsigned char *  pbuf,
int  pbufSize 
)

Definition at line 900 of file ISComm.c.

◆ is_decode_binary_packet_byte()

int is_decode_binary_packet_byte ( uint8_t **  _ptrSrc,
uint8_t **  _ptrDest,
uint32_t *  checksum,
uint32_t  shift 
)

Definition at line 761 of file ISComm.c.

◆ is_decode_binary_packet_footer()

void is_decode_binary_packet_footer ( packet_ftr_t ftr,
uint8_t *  ptrSrc,
uint8_t **  ptrSrcEnd,
uint32_t *  checksum 
)

Definition at line 704 of file ISComm.c.

◆ is_enable_packet_encoding()

void is_enable_packet_encoding ( int  enabled)

Definition at line 1002 of file ISComm.c.

◆ is_encode_binary_packet()

int is_encode_binary_packet ( void *  srcBuffer,
unsigned int  srcBufferLength,
packet_hdr_t hdr,
uint8_t  additionalPktFlags,
void *  encodedPacket,
int  encodedPacketLength 
)

Definition at line 791 of file ISComm.c.

◆ processAsciiPkt()

static protocol_type_t processAsciiPkt ( is_comm_instance_t instance)
static

Definition at line 294 of file ISComm.c.

◆ processInertialSensePkt()

static protocol_type_t processInertialSensePkt ( is_comm_instance_t instance)
static

Definition at line 218 of file ISComm.c.

◆ processRtcm3Byte()

static protocol_type_t processRtcm3Byte ( is_comm_instance_t instance)
static

Definition at line 405 of file ISComm.c.

◆ processUbloxByte()

static protocol_type_t processUbloxByte ( is_comm_instance_t instance)
static

Definition at line 328 of file ISComm.c.

◆ reset_parser()

static __inline void reset_parser ( is_comm_instance_t instance)
static

Definition at line 212 of file ISComm.c.

◆ sendData()

static int sendData ( is_comm_instance_t instance,
uint32_t  dataId,
uint32_t  offset,
uint32_t  size,
void *  data,
uint32_t  pid 
)
static

Definition at line 610 of file ISComm.c.

◆ swapPacket()

static void swapPacket ( packet_t pkt)
static

Definition at line 128 of file ISComm.c.

Variable Documentation

◆ g_validBaudRates

List of valid baud rates

Definition at line 84 of file ISComm.c.

◆ s_packetEncodingEnabled

int s_packetEncodingEnabled = 1
static

Definition at line 85 of file ISComm.c.



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