Classes | Macros | Typedefs | Enumerations | Functions | Variables
ISComm.h File Reference
#include "data_sets.h"
#include "stddef.h"
Include dependency graph for ISComm.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  asciiMessageMap_t
 
struct  buffer_t
 
struct  bufPtr_t
 
struct  bufTxRxPtr_t
 
struct  is_comm_buffer_t
 
struct  is_comm_config_t
 
struct  is_comm_instance_t
 
struct  p_ack_hdr_t
 
struct  p_ack_t
 
struct  p_data_disable_t
 
struct  p_data_get_t
 
struct  p_data_hdr_t
 
struct  p_data_t
 
struct  packet_ftr_t
 
struct  packet_hdr_t
 
struct  packet_t
 
struct  pkt_info_t
 

Macros

#define _DID_BAROMETER   DID_BAROMETER /** (see barometer_t) Barometric pressure sensor data */
 
#define _DID_BIT   DID_BIT /** (see bit_t) System built-in self-test */
 
#define _DID_DEV_INFO   DID_DEV_INFO /** (see dev_info_t) Device information */
 
#define _DID_FLASH_CONFIG   DID_FLASH_CONFIG /** (see nvm_flash_cfg_t) Flash memory configuration */
 
#define _DID_GPS1_POS   DID_GPS1_POS /** (see gps_pos_t) GPS output */
 
#define _DID_IMU_DUAL   DID_DUAL_IMU /** (see dual_imu_t) Dual IMU output: angular rate (rad/s) and linear acceleration (m/s^2) */
 
#define _DID_IMU_PREINTEGRATED_IMU   DID_PREINTEGRATED_IMU /** (see preintegrated_imu_t) Dual IMU output: Conning and sculling integrated at IMU update rate. */
 
#define _DID_INS_ECEF_QE2B   DID_INS_4 /** (see ins_4_t) INS output: ECEF position (m) and velocity (m/s), quaternion from ECEF */
 
#define _DID_INS_LLA_EULER_NED   DID_INS_1 /** (see ins_1_t) INS/AHRS output: euler from NED, LLA (degrees,m), NED pos (m) and vel (m/s) from refLLA */
 
#define _DID_INS_LLA_QN2B   DID_INS_3 /** (see ins_3_t) INS/AHRS output: quaternion from NED, LLA (degrees,m) */
 
#define _DID_MAG_CAL   DID_MAG_CAL /** (see mag_cal_t) Magnetometer calibration */
 
#define _DID_MAGNETOMETER_1   DID_MAGNETOMETER_1 /** (see magnetometer_t) Magnetometer sensor 1 output */
 
#define _DID_MAGNETOMETER_2   DID_MAGNETOMETER_2 /** (see magnetometer_t) Magnetometer sensor 2 output */
 
#define _DID_POS_MEASUREMENT   DID_POSITION_MEASUREMENT/** (see pos_measurement_t) Position Measurement data*/
 
#define _DID_RMC   DID_RMC /** (see rmc_t) Realtime message controller */
 
#define _DID_STROBE_IN_TIME   DID_STROBE_IN_TIME /** (see strobe_in_time_t) Timestamp for input strobe */
 
#define _DID_WHEEL_ENCODER   DID_WHEEL_ENCODER /** (see wheel_encoder_t) Wheel encoder sensor data */
 
#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]))
 
#define CHECKSUM_SEED   0x00AAAAAA
 
#define IS_COM_BAUDRATE_DEFAULT   IS_BAUDRATE_921600
 
#define MAX_DATASET_SIZE   1024
 
#define MAX_P_ACK_BODY_SIZE   (MAX_PKT_BODY_SIZE-sizeof(p_ack_hdr_t))
 
#define MAX_P_DATA_BODY_SIZE   (MAX_PKT_BODY_SIZE-sizeof(p_data_hdr_t))
 
#define MAX_PKT_BODY_SIZE   (((PKT_BUF_SIZE - MAX_PKT_OVERHEAD_SIZE) / 2) & 0xFFFFFFFE)
 
#define MAX_PKT_OVERHEAD_SIZE   (PKT_OVERHEAD_SIZE + PKT_OVERHEAD_SIZE - 2)
 
#define PID_ACK   (ePacketIDs)1 /** (ACK) received valid packet */
 
#define PID_COUNT   (ePacketIDs)9 /** The number of packet identifiers, keep this at the end! */
 
#define PID_DATA   (ePacketIDs)4 /** Data sent in response to PID_GET_DATA (no PID_ACK is sent) */
 
#define PID_GET_DATA   (ePacketIDs)3 /** Request for data to be broadcast, response is PID_DATA. See data structures for list of possible broadcast data. */
 
#define PID_INVALID   (ePacketIDs)0 /** Invalid packet id */
 
#define PID_MAX_COUNT   (ePacketIDs)32 /** The maximum count of packet identifiers, 0x1F (PACKET_INFO_ID_MASK) */
 
#define PID_NACK   (ePacketIDs)2 /** (NACK) received invalid packet */
 
#define PID_SET_DATA   (ePacketIDs)5 /** Data sent, such as configuration options. PID_ACK is sent in response. */
 
#define PID_STOP_BROADCASTS_ALL_PORTS   (ePacketIDs)6 /** Stop all data broadcasts on all ports. Responds with an ACK */
 
#define PID_STOP_BROADCASTS_CURRENT_PORT   (ePacketIDs)8 /** Stop all data broadcasts on current port. Responds with an ACK */
 
#define PID_STOP_DID_BROADCAST   (ePacketIDs)7 /** Stop a specific broadcast */
 
#define PKT_BUF_SIZE   2048
 
#define PKT_OVERHEAD_SIZE   8
 
#define PROTOCOL_VERSION_CHAR0   (1)
 
#define PROTOCOL_VERSION_CHAR1   (2)
 
#define RTCM3_HEADER_SIZE   3
 
#define UBLOX_HEADER_SIZE   6
 

Typedefs

typedef uint32_t ePacketIDs
 
typedef struct p_data_t p_data_set_t
 
typedef struct p_ack_t p_nack_t
 

Enumerations

enum  asciiDataType { asciiTypeInt = 0, asciiTypeUInt = 1, asciiTypeFloat = 2, asciiTypeDouble = 3 }
 
enum  baud_rate_t {
  IS_BAUDRATE_9600 = 9600, IS_BAUDRATE_19200 = 19200, IS_BAUDRATE_38400 = 38400, IS_BAUDRATE_57600 = 57600,
  IS_BAUDRATE_115200 = 115200, IS_BAUDRATE_230400 = 230400, IS_BAUDRATE_460800 = 460800, IS_BAUDRATE_921600 = 921600,
  IS_BAUDRATE_3000000 = 3000000, IS_BAUDRATE_COUNT = 9
}
 
enum  ePktHdrFlags {
  CM_PKT_FLAGS_LITTLE_ENDIAN = 0x01, CM_PKT_FLAGS_ENDIANNESS_MASK = 0x01, CM_PKT_FLAGS_RX_VALID_DATA = 0x02, CM_PKT_FLAGS_MORE_DATA_AVAILABLE = 0x04,
  CM_PKT_FLAGS_RAW_DATA_NO_SWAP = 0x08, CM_PKT_FLAGS_CHECKSUM_24_BIT = 0x10
}
 
enum  ePktSpecialChars {
  PSC_ASCII_START_BYTE = 0x24, PSC_ASCII_END_BYTE = 0x0A, PSC_START_BYTE = 0xFF, PSC_END_BYTE = 0xFE,
  PSC_RESERVED_KEY = 0xFD, UBLOX_START_BYTE1 = 0xB5, UBLOX_START_BYTE2 = 0x62, RTCM3_START_BYTE = 0xD3
}
 
enum  protocol_type_t {
  _PTYPE_NONE = 0, _PTYPE_PARSE_ERROR = 0xFFFFFFFF, _PTYPE_INERTIAL_SENSE_DATA = 0xEFFFFFFF, _PTYPE_INERTIAL_SENSE_CMD = 0xDFFFFFFF,
  _PTYPE_INERTIAL_SENSE_ACK = 0xCFFFFFFF, _PTYPE_ASCII_NMEA = 0xBFFFFFFF, _PTYPE_UBLOX = 0xAFFFFFFF, _PTYPE_RTCM3 = 0x9FFFFFFF
}
 

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)
 
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 *com, 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)
 
POP_PACK 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)
 

Variables

const unsigned int g_validBaudRates [IS_BAUDRATE_COUNT]
 

Macro Definition Documentation

◆ _DID_BAROMETER

#define _DID_BAROMETER   DID_BAROMETER /** (see barometer_t) Barometric pressure sensor data */

Definition at line 61 of file ISComm.h.

◆ _DID_BIT

#define _DID_BIT   DID_BIT /** (see bit_t) System built-in self-test */

Definition at line 67 of file ISComm.h.

◆ _DID_DEV_INFO

#define _DID_DEV_INFO   DID_DEV_INFO /** (see dev_info_t) Device information */

Utilities

Definition at line 66 of file ISComm.h.

◆ _DID_FLASH_CONFIG

#define _DID_FLASH_CONFIG   DID_FLASH_CONFIG /** (see nvm_flash_cfg_t) Flash memory configuration */

Configuration

Definition at line 71 of file ISComm.h.

◆ _DID_GPS1_POS

#define _DID_GPS1_POS   DID_GPS1_POS /** (see gps_pos_t) GPS output */

GPS

Definition at line 55 of file ISComm.h.

◆ _DID_IMU_DUAL

#define _DID_IMU_DUAL   DID_DUAL_IMU /** (see dual_imu_t) Dual IMU output: angular rate (rad/s) and linear acceleration (m/s^2) */

IMU

Definition at line 51 of file ISComm.h.

◆ _DID_IMU_PREINTEGRATED_IMU

#define _DID_IMU_PREINTEGRATED_IMU   DID_PREINTEGRATED_IMU /** (see preintegrated_imu_t) Dual IMU output: Conning and sculling integrated at IMU update rate. */

Definition at line 52 of file ISComm.h.

◆ _DID_INS_ECEF_QE2B

#define _DID_INS_ECEF_QE2B   DID_INS_4 /** (see ins_4_t) INS output: ECEF position (m) and velocity (m/s), quaternion from ECEF */

DEFINITIONS AND CONVENTIONS

INS = inertial navigation system AHRS = attitude heading reference system IMU = inertial measurement unit: gyros (rad/s), accelerometers (m/s^2) ECEF = earth-centered earth fixed: x,y,z or vx,vy,vz (m or m/s) LLA = latitude, longitude, altitude (degrees,m) NED = north, east, down (m or m/s) QE2B = quaternion rotation from ECEF frame to local frame. QN2B = quaternion rotation from NED frame to local frame. UVW = velocities in local frame.INS/AHRS

Definition at line 46 of file ISComm.h.

◆ _DID_INS_LLA_EULER_NED

#define _DID_INS_LLA_EULER_NED   DID_INS_1 /** (see ins_1_t) INS/AHRS output: euler from NED, LLA (degrees,m), NED pos (m) and vel (m/s) from refLLA */

Definition at line 47 of file ISComm.h.

◆ _DID_INS_LLA_QN2B

#define _DID_INS_LLA_QN2B   DID_INS_3 /** (see ins_3_t) INS/AHRS output: quaternion from NED, LLA (degrees,m) */

Definition at line 48 of file ISComm.h.

◆ _DID_MAG_CAL

#define _DID_MAG_CAL   DID_MAG_CAL /** (see mag_cal_t) Magnetometer calibration */

Magnetometer, Barometer, and other Sensor

Definition at line 58 of file ISComm.h.

◆ _DID_MAGNETOMETER_1

#define _DID_MAGNETOMETER_1   DID_MAGNETOMETER_1 /** (see magnetometer_t) Magnetometer sensor 1 output */

Definition at line 59 of file ISComm.h.

◆ _DID_MAGNETOMETER_2

#define _DID_MAGNETOMETER_2   DID_MAGNETOMETER_2 /** (see magnetometer_t) Magnetometer sensor 2 output */

Definition at line 60 of file ISComm.h.

◆ _DID_POS_MEASUREMENT

#define _DID_POS_MEASUREMENT   DID_POSITION_MEASUREMENT/** (see pos_measurement_t) Position Measurement data*/

Definition at line 63 of file ISComm.h.

◆ _DID_RMC

#define _DID_RMC   DID_RMC /** (see rmc_t) Realtime message controller */

Definition at line 72 of file ISComm.h.

◆ _DID_STROBE_IN_TIME

#define _DID_STROBE_IN_TIME   DID_STROBE_IN_TIME /** (see strobe_in_time_t) Timestamp for input strobe */

Definition at line 68 of file ISComm.h.

◆ _DID_WHEEL_ENCODER

#define _DID_WHEEL_ENCODER   DID_WHEEL_ENCODER /** (see wheel_encoder_t) Wheel encoder sensor data */

Definition at line 62 of file ISComm.h.

◆ ASCII_MESSAGEID_TO_UINT

#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]))

create a uint from an ASCII message id that is the same, regardless of CPU architecture

Definition at line 242 of file ISComm.h.

◆ CHECKSUM_SEED

#define CHECKSUM_SEED   0x00AAAAAA

Binary checksum start value

Definition at line 114 of file ISComm.h.

◆ IS_COM_BAUDRATE_DEFAULT

#define IS_COM_BAUDRATE_DEFAULT   IS_BAUDRATE_921600

uINS default baud rate

Definition at line 88 of file ISComm.h.

◆ MAX_DATASET_SIZE

#define MAX_DATASET_SIZE   1024

The maximum allowable dataset size

Definition at line 91 of file ISComm.h.

◆ MAX_P_ACK_BODY_SIZE

#define MAX_P_ACK_BODY_SIZE   (MAX_PKT_BODY_SIZE-sizeof(p_ack_hdr_t))

The maximum size of a decoded ACK message

Definition at line 111 of file ISComm.h.

◆ MAX_P_DATA_BODY_SIZE

#define MAX_P_DATA_BODY_SIZE   (MAX_PKT_BODY_SIZE-sizeof(p_data_hdr_t))

The maximum size of decoded data in a packet body

Definition at line 108 of file ISComm.h.

◆ MAX_PKT_BODY_SIZE

#define MAX_PKT_BODY_SIZE   (((PKT_BUF_SIZE - MAX_PKT_OVERHEAD_SIZE) / 2) & 0xFFFFFFFE)

The maximum size of an decoded packet body

Definition at line 105 of file ISComm.h.

◆ MAX_PKT_OVERHEAD_SIZE

#define MAX_PKT_OVERHEAD_SIZE   (PKT_OVERHEAD_SIZE + PKT_OVERHEAD_SIZE - 2)

The maximum encoded overhead size in sending a packet (7 bytes for header, 7 bytes for footer). The packet start and end bytes are never encoded.

Definition at line 102 of file ISComm.h.

◆ PID_ACK

#define PID_ACK   (ePacketIDs)1 /** (ACK) received valid packet */

Definition at line 181 of file ISComm.h.

◆ PID_COUNT

#define PID_COUNT   (ePacketIDs)9 /** The number of packet identifiers, keep this at the end! */

Definition at line 189 of file ISComm.h.

◆ PID_DATA

#define PID_DATA   (ePacketIDs)4 /** Data sent in response to PID_GET_DATA (no PID_ACK is sent) */

Definition at line 184 of file ISComm.h.

◆ PID_GET_DATA

#define PID_GET_DATA   (ePacketIDs)3 /** Request for data to be broadcast, response is PID_DATA. See data structures for list of possible broadcast data. */

Definition at line 183 of file ISComm.h.

◆ PID_INVALID

#define PID_INVALID   (ePacketIDs)0 /** Invalid packet id */

Definition at line 180 of file ISComm.h.

◆ PID_MAX_COUNT

#define PID_MAX_COUNT   (ePacketIDs)32 /** The maximum count of packet identifiers, 0x1F (PACKET_INFO_ID_MASK) */

Definition at line 190 of file ISComm.h.

◆ PID_NACK

#define PID_NACK   (ePacketIDs)2 /** (NACK) received invalid packet */

Definition at line 182 of file ISComm.h.

◆ PID_SET_DATA

#define PID_SET_DATA   (ePacketIDs)5 /** Data sent, such as configuration options. PID_ACK is sent in response. */

Definition at line 185 of file ISComm.h.

◆ PID_STOP_BROADCASTS_ALL_PORTS

#define PID_STOP_BROADCASTS_ALL_PORTS   (ePacketIDs)6 /** Stop all data broadcasts on all ports. Responds with an ACK */

Definition at line 186 of file ISComm.h.

◆ PID_STOP_BROADCASTS_CURRENT_PORT

#define PID_STOP_BROADCASTS_CURRENT_PORT   (ePacketIDs)8 /** Stop all data broadcasts on current port. Responds with an ACK */

Definition at line 188 of file ISComm.h.

◆ PID_STOP_DID_BROADCAST

#define PID_STOP_DID_BROADCAST   (ePacketIDs)7 /** Stop a specific broadcast */

Definition at line 187 of file ISComm.h.

◆ PKT_BUF_SIZE

#define PKT_BUF_SIZE   2048

The maximum buffer space that is used for sending and receiving packets

Definition at line 98 of file ISComm.h.

◆ PKT_OVERHEAD_SIZE

#define PKT_OVERHEAD_SIZE   8

The decoded overhead involved in sending a packet - 4 bytes for header, 4 bytes for footer

Definition at line 94 of file ISComm.h.

◆ PROTOCOL_VERSION_CHAR0

#define PROTOCOL_VERSION_CHAR0   (1)

Defines the 4 parts to the communications version. Major changes involve changes to the com manager. Minor changes involve additions to data structures

Definition at line 119 of file ISComm.h.

◆ PROTOCOL_VERSION_CHAR1

#define PROTOCOL_VERSION_CHAR1   (2)

Definition at line 123 of file ISComm.h.

◆ RTCM3_HEADER_SIZE

#define RTCM3_HEADER_SIZE   3

Definition at line 130 of file ISComm.h.

◆ UBLOX_HEADER_SIZE

#define UBLOX_HEADER_SIZE   6

Definition at line 129 of file ISComm.h.

Typedef Documentation

◆ ePacketIDs

typedef uint32_t ePacketIDs

Definition at line 178 of file ISComm.h.

◆ p_data_set_t

typedef struct p_data_t p_data_set_t

◆ p_nack_t

typedef struct p_ack_t p_nack_t

Enumeration Type Documentation

◆ asciiDataType

Types of values allowed in ASCII data

Enumerator
asciiTypeInt 

32 bit integer

asciiTypeUInt 

32 bit unsigned integer

asciiTypeFloat 

32 bit floating point

asciiTypeDouble 

64 bit floating point

Definition at line 226 of file ISComm.h.

◆ baud_rate_t

We must not allow any packing or shifting as these data structures must match exactly in memory on all devices Valid baud rates for Inertial Sense hardware

Enumerator
IS_BAUDRATE_9600 
IS_BAUDRATE_19200 
IS_BAUDRATE_38400 
IS_BAUDRATE_57600 
IS_BAUDRATE_115200 
IS_BAUDRATE_230400 
IS_BAUDRATE_460800 
IS_BAUDRATE_921600 
IS_BAUDRATE_3000000 
IS_BAUDRATE_COUNT 

Definition at line 136 of file ISComm.h.

◆ ePktHdrFlags

Enumerator
CM_PKT_FLAGS_LITTLE_ENDIAN 
CM_PKT_FLAGS_ENDIANNESS_MASK 
CM_PKT_FLAGS_RX_VALID_DATA 
CM_PKT_FLAGS_MORE_DATA_AVAILABLE 
CM_PKT_FLAGS_RAW_DATA_NO_SWAP 
CM_PKT_FLAGS_CHECKSUM_24_BIT 

Definition at line 244 of file ISComm.h.

◆ ePktSpecialChars

Built in special bytes that will need to be encoded in the binary packet format. This is not an exhaustive list, as other bytes such as ublox and rtcm preambles will be encoded as well, but these messages are not parsed and handled in the com manager, rather they are forwarded via the pass through handler. A byte is encoded by writing a 0xFD byte (encoded byte marker), followed by the encoded byte, which is created by inverting all the bits of the original byte. These bytes are not encoded when written in the proper spot in the packet (i.e. when writing the first byte for a binary packet, the 0xFF byte, no encoding is performed).

Enumerator
PSC_ASCII_START_BYTE 

Dollar sign ($), used by ASCII protocol to signify start of message (36)

PSC_ASCII_END_BYTE 

New line (
), used by ASCII protocol to signify end of message (10)

PSC_START_BYTE 

Binary packet start byte, must only exist at the very start of a binary packet and no where else (255)

PSC_END_BYTE 

Binary packet end byte, must only exist at the end of a binary packet and no where else (254)

PSC_RESERVED_KEY 

Encoded byte marker, must only be used to prefix encoded bytes (253)

UBLOX_START_BYTE1 

Ublox start byte 1 (181)

UBLOX_START_BYTE2 

Ublox start byte 2 (98)

RTCM3_START_BYTE 

Rtcm3 start byte (211)

Definition at line 270 of file ISComm.h.

◆ protocol_type_t

Protocol Type

Enumerator
_PTYPE_NONE 
_PTYPE_PARSE_ERROR 

No complete valid data available yet

_PTYPE_INERTIAL_SENSE_DATA 

Invalid data or checksum error

_PTYPE_INERTIAL_SENSE_CMD 

Protocol Type: Inertial Sense binary data

_PTYPE_INERTIAL_SENSE_ACK 

Protocol Type: Inertial Sense binary command (i.e. query data)

_PTYPE_ASCII_NMEA 

Protocol Type: Inertial Sense binary acknowledge (ack) or negative acknowledge (nack)

_PTYPE_UBLOX 

Protocol Type: ASCII NMEA (National Marine Electronics Association)

_PTYPE_RTCM3 

Protocol Type: uBlox binary

Definition at line 75 of file ISComm.h.

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.

◆ 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 is_comm_instance data into a data structure. Returns 0 on success, -1 on failure.

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()

POP_PACK 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.

Variable Documentation

◆ g_validBaudRates

const unsigned int g_validBaudRates[IS_BAUDRATE_COUNT]

List of valid baud rates

Definition at line 84 of file ISComm.c.



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