Classes | Macros | Typedefs | Functions
com_manager.h File Reference
#include <stdint.h>
#include "ISComm.h"
#include "linked_list.h"
Include dependency graph for com_manager.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  broadcast_msg_t
 
struct  com_manager_init_t
 
struct  com_manager_port_t
 
struct  com_manager_status_t
 
struct  com_manager_t
 
struct  ensured_pkt_t
 
struct  registered_data_t
 

Macros

#define COM_MANAGER_BUF_SIZE_BCAST_MSG(max_num_bcast_msgs)   ((max_num_bcast_msgs)*sizeof(broadcast_msg_t))
 
#define COM_MANAGER_BUF_SIZE_ENSURED_PKTS(max_num_ensured_pkts)   ((max_num_ensured_pkts)*sizeof(ensured_pkt_t))
 
#define ENABLE_PACKET_CONTINUATION   0
 
#define MAX_NUM_BCAST_MSGS   8
 

Typedefs

typedef void * CMHANDLE
 
typedef int(* pfnComManagerAsapMsg) (CMHANDLE cmHandle, int pHandle, p_data_get_t *req)
 
typedef void(* pfnComManagerDisableBroadcasts) (CMHANDLE cmHandle, int pHandle)
 
typedef int(* pfnComManagerGenMsgHandler) (CMHANDLE cmHandle, int pHandle, const unsigned char *msg, int msgSize)
 
typedef void(* pfnComManagerPostAck) (CMHANDLE cmHandle, int pHandle, p_ack_t *ack, unsigned char packetIdentifier)
 
typedef void(* pfnComManagerPostRead) (CMHANDLE cmHandle, int pHandle, p_data_t *dataRead)
 
typedef void(* pfnComManagerPreSend) (CMHANDLE cmHandle, int pHandle)
 
typedef int(* pfnComManagerRead) (CMHANDLE cmHandle, int pHandle, uint8_t *buffer, int numberOfBytes)
 
typedef int(* pfnComManagerSend) (CMHANDLE cmHandle, int pHandle, unsigned char *buffer, int numberOfBytes)
 
typedef int(* pfnComManagerSendBufferAvailableBytes) (CMHANDLE cmHandle, int pHandle)
 

Functions

void comManagerAssignUserPointer (CMHANDLE cmInstance, void *userPointer)
 
void comManagerDisableBroadcasts (int pHandle)
 
void comManagerDisableBroadcastsInstance (CMHANDLE cmInstance, int pHandle)
 
int comManagerDisableData (int pHandle, uint32_t dataId)
 
int comManagerDisableDataInstance (CMHANDLE cmInstance, int pHandle, uint32_t dataId)
 
void comManagerGetData (int pHandle, uint32_t dataId, int offset, int size, int periodMultiple)
 Request data This function requests the specified data w/ offset and length for partial reads. More...
 
void comManagerGetDataInstance (CMHANDLE cmInstance, int pHandle, uint32_t dataId, int offset, int size, int periodMultiple)
 
int comManagerGetDataRequest (int pHandle, p_data_get_t *req)
 
int comManagerGetDataRequestInstance (CMHANDLE cmInstance, int pHandle, p_data_get_t *req)
 
void comManagerGetDataRmc (int pHandle, uint64_t rmcBits, uint32_t rmcOptions)
 
void comManagerGetDataRmcInstance (CMHANDLE cmInstance, int pHandle, uint64_t rmcBits, uint32_t rmcOptions)
 
CMHANDLE comManagerGetGlobal (void)
 
bufTxRxPtr_tcomManagerGetRegisteredDataInfo (uint32_t dataId)
 
bufTxRxPtr_tcomManagerGetRegisteredDataInfoInstance (CMHANDLE cmInstance, uint32_t dataId)
 
com_manager_status_tcomManagerGetStatus (int pHandle)
 
com_manager_status_tcomManagerGetStatusInstance (CMHANDLE cmInstance, int pHandle)
 
void * comManagerGetUserPointer (CMHANDLE cmInstance)
 
int comManagerInit (int numHandles, int maxEnsuredPackets, int stepPeriodMilliseconds, int retryCount, pfnComManagerRead readFnc, pfnComManagerSend sendFnc, pfnComManagerSendBufferAvailableBytes txFreeFnc, pfnComManagerPostRead pstRxFnc, pfnComManagerPostAck pstAckFnc, pfnComManagerDisableBroadcasts disableBcastFnc, com_manager_init_t *buffers, com_manager_port_t *cmPorts)
 
int comManagerInitInstance (CMHANDLE cmHandle, int numHandles, int maxEnsuredPackets, int stepPeriodMilliseconds, int retryCount, pfnComManagerRead readFnc, pfnComManagerSend sendFnc, pfnComManagerSendBufferAvailableBytes txFreeFnc, pfnComManagerPostRead pstRxFnc, pfnComManagerPostAck pstAckFnc, pfnComManagerDisableBroadcasts disableBcastFnc, com_manager_init_t *buffers, com_manager_port_t *cmPorts)
 
void comManagerRegister (uint32_t dataId, pfnComManagerPreSend txFnc, pfnComManagerPostRead pstRxFnc, const void *txDataPtr, void *rxDataPtr, int dataSize, uint8_t pktFlags)
 
void comManagerRegisterInstance (CMHANDLE cmInstance, uint32_t dataId, pfnComManagerPreSend txFnc, pfnComManagerPostRead pstRxFnc, const void *txDataPtr, void *rxDataPtr, int dataSize, uint8_t pktFlags)
 
int comManagerSend (int pHandle, uint8_t pktInfo, bufPtr_t *bodyHdr, bufPtr_t *txData, uint8_t pktFlags)
 
int comManagerSendData (int pHandle, uint32_t dataId, void *dataPtr, int dataSize, int dataOffset)
 
int comManagerSendDataInstance (CMHANDLE cmInstance, int pHandle, uint32_t dataId, void *dataPtr, int dataSize, int dataOffset)
 
int comManagerSendDataNoAck (int pHandle, uint32_t dataId, void *dataPtr, int dataSize, int dataOffset)
 
int comManagerSendDataNoAckInstance (CMHANDLE cmInstance, int pHandle, uint32_t dataId, void *dataPtr, int dataSize, int dataOffset)
 
int comManagerSendEnsured (int pHandle, uint8_t pktInfo, unsigned char *data, unsigned int dataSize)
 
int comManagerSendEnsuredInstance (CMHANDLE cmInstance, int pHandle, uint8_t pktInfo, unsigned char *data, unsigned int dataSize)
 
int comManagerSendInstance (CMHANDLE cmInstance, int pHandle, uint8_t pktInfo, bufPtr_t *bodyHdr, bufPtr_t *txData, uint8_t pktFlags)
 
int comManagerSendRawData (int pHandle, uint32_t dataId, void *dataPtr, int dataSize, int dataOffset)
 
int comManagerSendRawDataInstance (CMHANDLE cmInstance, int pHandle, uint32_t dataId, void *dataPtr, int dataSize, int dataOffset)
 
void comManagerSetCallbacks (pfnComManagerAsapMsg rmcHandler, pfnComManagerGenMsgHandler asciiHandler, pfnComManagerGenMsgHandler ubloxHandler, pfnComManagerGenMsgHandler rtcm3Handler)
 
void comManagerSetCallbacksInstance (CMHANDLE cmInstance, pfnComManagerAsapMsg rmcHandler, pfnComManagerGenMsgHandler asciiHandler, pfnComManagerGenMsgHandler ubloxHandler, pfnComManagerGenMsgHandler rtcm3Handler)
 
void comManagerStep (void)
 
void comManagerStepInstance (CMHANDLE cmInstance_)
 
void comManagerStepRxInstance (CMHANDLE cmInstance)
 
void comManagerStepTxInstance (CMHANDLE cmInstance)
 
int comManagerValidateBaudRate (unsigned int baudRate)
 

Macro Definition Documentation

◆ COM_MANAGER_BUF_SIZE_BCAST_MSG

#define COM_MANAGER_BUF_SIZE_BCAST_MSG (   max_num_bcast_msgs)    ((max_num_bcast_msgs)*sizeof(broadcast_msg_t))

Definition at line 115 of file com_manager.h.

◆ COM_MANAGER_BUF_SIZE_ENSURED_PKTS

#define COM_MANAGER_BUF_SIZE_ENSURED_PKTS (   max_num_ensured_pkts)    ((max_num_ensured_pkts)*sizeof(ensured_pkt_t))

Definition at line 116 of file com_manager.h.

◆ ENABLE_PACKET_CONTINUATION

#define ENABLE_PACKET_CONTINUATION   0

Definition at line 25 of file com_manager.h.

◆ MAX_NUM_BCAST_MSGS

#define MAX_NUM_BCAST_MSGS   8

Maximum number of messages that may be broadcast simultaneously, per port. Since most messages use the RMC (real-time message controller) now, this can be fairly low

Definition at line 112 of file com_manager.h.

Typedef Documentation

◆ CMHANDLE

typedef void* CMHANDLE

Definition at line 119 of file com_manager.h.

◆ pfnComManagerAsapMsg

typedef int(* pfnComManagerAsapMsg) (CMHANDLE cmHandle, int pHandle, p_data_get_t *req)

Definition at line 153 of file com_manager.h.

◆ pfnComManagerDisableBroadcasts

typedef void(* pfnComManagerDisableBroadcasts) (CMHANDLE cmHandle, int pHandle)

Definition at line 138 of file com_manager.h.

◆ pfnComManagerGenMsgHandler

typedef int(* pfnComManagerGenMsgHandler) (CMHANDLE cmHandle, int pHandle, const unsigned char *msg, int msgSize)

Definition at line 147 of file com_manager.h.

◆ pfnComManagerPostAck

typedef void(* pfnComManagerPostAck) (CMHANDLE cmHandle, int pHandle, p_ack_t *ack, unsigned char packetIdentifier)

Definition at line 135 of file com_manager.h.

◆ pfnComManagerPostRead

typedef void(* pfnComManagerPostRead) (CMHANDLE cmHandle, int pHandle, p_data_t *dataRead)

Definition at line 132 of file com_manager.h.

◆ pfnComManagerPreSend

typedef void(* pfnComManagerPreSend) (CMHANDLE cmHandle, int pHandle)

Definition at line 141 of file com_manager.h.

◆ pfnComManagerRead

typedef int(* pfnComManagerRead) (CMHANDLE cmHandle, int pHandle, uint8_t *buffer, int numberOfBytes)

Definition at line 123 of file com_manager.h.

◆ pfnComManagerSend

typedef int(* pfnComManagerSend) (CMHANDLE cmHandle, int pHandle, unsigned char *buffer, int numberOfBytes)

Definition at line 126 of file com_manager.h.

◆ pfnComManagerSendBufferAvailableBytes

typedef int(* pfnComManagerSendBufferAvailableBytes) (CMHANDLE cmHandle, int pHandle)

Definition at line 129 of file com_manager.h.

Function Documentation

◆ comManagerAssignUserPointer()

void comManagerAssignUserPointer ( CMHANDLE  cmInstance,
void *  userPointer 
)

Attach user defined data to a com manager instance

Definition at line 472 of file com_manager.c.

◆ comManagerDisableBroadcasts()

void comManagerDisableBroadcasts ( int  pHandle)

Disables broadcasts of all messages on specified port, or all ports if phandle == -1.

Parameters
pHandlethe pHandle to disable broadcasts on, -1 for all

Definition at line 1043 of file com_manager.c.

◆ comManagerDisableBroadcastsInstance()

void comManagerDisableBroadcastsInstance ( CMHANDLE  cmInstance,
int  pHandle 
)

Definition at line 1048 of file com_manager.c.

◆ comManagerDisableData()

int comManagerDisableData ( int  pHandle,
uint32_t  dataId 
)

Disable a broadcast for a specified port handle and data identifier

Parameters
pHandlethe port handle to disable a broadcast for
dataIdthe data id to disable boradcast for
Returns
0 if success, anything else if failure

Example:

Definition at line 620 of file com_manager.c.

◆ comManagerDisableDataInstance()

int comManagerDisableDataInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint32_t  dataId 
)

Definition at line 625 of file com_manager.c.

◆ comManagerGetData()

void comManagerGetData ( int  pHandle,
uint32_t  dataId,
int  offset,
int  size,
int  periodMultiple 
)

Request data This function requests the specified data w/ offset and length for partial reads.

Make a request to a port handle to broadcast a piece of data at a set interval.

Parameters
pHandlethe port handle to request broadcast data from
dataIdthe data id to broadcast
offsetoffset into the structure for the data id to broadcast - pass offset and size of 0 to receive the entire data set
sizenumber of bytes in the data structure from offset to broadcast - pass offset and size of 0 to receive the entire data set
periodMultiplethe data broadcast period in multiples of the base update period

Example that makes a request to receive the device info just once:

Example that broadcasts INS data every 50 milliseconds:

comManagerGetData(0, DID_INS_1, 0, sizeof(ins_1_t), 50);
Parameters
[in]dataIdData structure ID
[in]offsetByte offset into data structure. 0 = data start.
[in]lengthByte length of data. 0 = entire structure.
[in]periodMultipleBroadcast period of requested data. 0 = single request.
Returns
0 on successful request. -1 on failure.

Definition at line 511 of file com_manager.c.

◆ comManagerGetDataInstance()

void comManagerGetDataInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint32_t  dataId,
int  offset,
int  size,
int  periodMultiple 
)

Definition at line 516 of file com_manager.c.

◆ comManagerGetDataRequest()

int comManagerGetDataRequest ( int  pHandle,
p_data_get_t req 
)

Internal use mostly, process a get data request for a message that needs to be broadcasted

Returns
0 on success, anything else is failure

Definition at line 889 of file com_manager.c.

◆ comManagerGetDataRequestInstance()

int comManagerGetDataRequestInstance ( CMHANDLE  cmInstance,
int  pHandle,
p_data_get_t req 
)

Definition at line 894 of file com_manager.c.

◆ comManagerGetDataRmc()

void comManagerGetDataRmc ( int  pHandle,
uint64_t  rmcBits,
uint32_t  rmcOptions 
)

Make a request to a port handle to broadcast a piece of data at a set interval.

Parameters
pHandlethe port handle to request broadcast data from
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
RMCoptions to enable data streaming on ports other than the current port.
offsetoffset into the structure for the data id to broadcast - pass offset and size of 0 to receive the entire data set
sizenumber of bytes in the data structure from offset to broadcast - pass offset and size of 0 to receive the entire data set
periodMultiplethe data broadcast period in multiples of the base update period

Example that enables streaming of all data messages necessary for post processing:

Example that broadcasts INS and GPS data at full rate:

Definition at line 534 of file com_manager.c.

◆ comManagerGetDataRmcInstance()

void comManagerGetDataRmcInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint64_t  rmcBits,
uint32_t  rmcOptions 
)

Definition at line 539 of file com_manager.c.

◆ comManagerGetGlobal()

CMHANDLE comManagerGetGlobal ( void  )

Definition at line 76 of file com_manager.c.

◆ comManagerGetRegisteredDataInfo()

bufTxRxPtr_t* comManagerGetRegisteredDataInfo ( uint32_t  dataId)

Internal use mostly, get data info for a the specified pre-registered dataId

Returns
0 on failure, pointer on success

Definition at line 872 of file com_manager.c.

◆ comManagerGetRegisteredDataInfoInstance()

bufTxRxPtr_t* comManagerGetRegisteredDataInfoInstance ( CMHANDLE  cmInstance,
uint32_t  dataId 
)

Definition at line 877 of file com_manager.c.

◆ comManagerGetStatus()

com_manager_status_t* comManagerGetStatus ( int  pHandle)

Get the most recent status of the com manager

Returns
com manager status, this pointer is owned by the com manager

Definition at line 482 of file com_manager.c.

◆ comManagerGetStatusInstance()

com_manager_status_t* comManagerGetStatusInstance ( CMHANDLE  cmInstance,
int  pHandle 
)

Definition at line 487 of file com_manager.c.

◆ comManagerGetUserPointer()

void* comManagerGetUserPointer ( CMHANDLE  cmInstance)

Get user defined data to from a com manager instance

Definition at line 477 of file com_manager.c.

◆ comManagerInit()

int comManagerInit ( int  numHandles,
int  maxEnsuredPackets,
int  stepPeriodMilliseconds,
int  retryCount,
pfnComManagerRead  readFnc,
pfnComManagerSend  sendFnc,
pfnComManagerSendBufferAvailableBytes  txFreeFnc,
pfnComManagerPostRead  pstRxFnc,
pfnComManagerPostAck  pstAckFnc,
pfnComManagerDisableBroadcasts  disableBcastFnc,
com_manager_init_t buffers,
com_manager_port_t cmPorts 
)

Initializes the default global com manager. This is generally only called once on program start. The global com manager is used by the functions that do not have the Instance suffix and first parameter of void* cmInstance. The instance functions can be ignored, unless you have a reason to have two com managers in the same process.

Parameters
numHandlesthe max number of serial ports possible
maxEnsuredPacketsthe max number of ensured packets
stepPeriodMillisecondshow many milliseconds you are waiting in between calls to comManagerStep
retryCountthe number of times to retry failed packets
readFncread data from the serial port represented by pHandle
sendFncsend data to the serial port represented by pHandle
txFreeFncoptional, return the number of free bytes in the send buffer for the serial port represented by pHandle
pstRxFncoptional, called after new data is available (successfully parsed and checksum passed) from the serial port represented by pHandle
pstAckFncoptional, called after an ACK is received by the serial port represented by pHandle
disableBcastFncmostly for internal use, this can be left as 0 or NULL
Returns
0 on success, -1 on failure

Example:

comManagerInit(20, 20, 10, 25, staticReadPacket, staticSendPacket, NULL, staticProcessRxData, staticProcessAck, 0);

Definition at line 79 of file com_manager.c.

◆ comManagerInitInstance()

int comManagerInitInstance ( CMHANDLE  cmHandle,
int  numHandles,
int  maxEnsuredPackets,
int  stepPeriodMilliseconds,
int  retryCount,
pfnComManagerRead  readFnc,
pfnComManagerSend  sendFnc,
pfnComManagerSendBufferAvailableBytes  txFreeFnc,
pfnComManagerPostRead  pstRxFnc,
pfnComManagerPostAck  pstAckFnc,
pfnComManagerDisableBroadcasts  disableBcastFnc,
com_manager_init_t buffers,
com_manager_port_t cmPorts 
)

Definition at line 111 of file com_manager.c.

◆ comManagerRegister()

void comManagerRegister ( uint32_t  dataId,
pfnComManagerPreSend  txFnc,
pfnComManagerPostRead  pstRxFnc,
const void *  txDataPtr,
void *  rxDataPtr,
int  dataSize,
uint8_t  pktFlags 
)

Register message handling function for a received data id (binary). This is mostly an internal use function, but can be used if you are implementing your own receiver on a device.

Parameters
dataIdthe data id to register the handler for
txFnccalled right before the data is sent
pstRxFnccalled after data is received for the data id
txDataPtra pointer to the structure in memory of the data to send
rxDataPtra pointer to the structure in memory to copy received data to
dataSizesize of the data structure in txDataPtr and rxDataPtr
pktFlagspacket flags, usually 0

Example:

registerComManager(DID_INS_1, prepMsgINS, writeMsgINS, &g_insData, &g_insData, sizeof(ins_1_t));

Definition at line 247 of file com_manager.c.

◆ comManagerRegisterInstance()

void comManagerRegisterInstance ( CMHANDLE  cmInstance,
uint32_t  dataId,
pfnComManagerPreSend  txFnc,
pfnComManagerPostRead  pstRxFnc,
const void *  txDataPtr,
void *  rxDataPtr,
int  dataSize,
uint8_t  pktFlags 
)

Definition at line 252 of file com_manager.c.

◆ comManagerSend()

int comManagerSend ( int  pHandle,
uint8_t  pktInfo,
bufPtr_t bodyHdr,
bufPtr_t txData,
uint8_t  pktFlags 
)

Send a packet to a port handle

Parameters
pHandlethe port handle to send the packet to
pktInfothe type of packet (PID)
bodyHdroptional, can contain information about the actual data of the body (txData), usually the data id, offset and size
txDataoptional, the actual body of the packet
Returns
0 if success, anything else if failure

Example:

p_data_get_t request;
request.id = DID_INS_1;
request.offset = 0;
request.size = sizeof(ins_1_t);
request.bc_period_ms = 50;
data.ptr = (uint8_t*)&request;
data.size = sizeof(request);
comManagerSend(pHandle, PID_GET_DATA, 0, &data)

Definition at line 634 of file com_manager.c.

◆ comManagerSendData()

int comManagerSendData ( int  pHandle,
uint32_t  dataId,
void *  dataPtr,
int  dataSize,
int  dataOffset 
)

Convenience function that wraps comManagerSend for sending data structures. Must be multiple of 4 bytes in size.

Parameters
pHandlethe port handle to send data to
dataIdthe data id of the data to send
dataPtrpointer to the data structure to send
dataSizenumber of bytes to send
dataOffsetoffset into dataPtr to send at
Returns
0 if success, anything else if failure

Example:

comManagerSendData(0, DID_DEV_INFO, &g_devInfo, sizeof(dev_info_t), 0);

Definition at line 548 of file com_manager.c.

◆ comManagerSendDataInstance()

int comManagerSendDataInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint32_t  dataId,
void *  dataPtr,
int  dataSize,
int  dataOffset 
)

Definition at line 553 of file com_manager.c.

◆ comManagerSendDataNoAck()

int comManagerSendDataNoAck ( int  pHandle,
uint32_t  dataId,
void *  dataPtr,
int  dataSize,
int  dataOffset 
)

Same as comManagerSend, except that no retry is attempted

Parameters
pHandlethe port handle to send the packet to
dataIdData structure ID number.
dataPtrPointer to actual data.
dataSizeSize of data to send in number of bytes.
dataOffsetOffset into data structure where copied data starts.
pFlagsAdditional packet flags if needed.
Returns
0 if success, anything else if failure

Definition at line 572 of file com_manager.c.

◆ comManagerSendDataNoAckInstance()

int comManagerSendDataNoAckInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint32_t  dataId,
void *  dataPtr,
int  dataSize,
int  dataOffset 
)

Definition at line 577 of file com_manager.c.

◆ comManagerSendEnsured()

int comManagerSendEnsured ( int  pHandle,
uint8_t  pktInfo,
unsigned char *  data,
unsigned int  dataSize 
)

Same as comManagerSend, except that the com manager may retry the send if an ACK is not received

Parameters
pHandlethe port handle to send the packet to
pktInfothe type of packet (PID)
bodyHdroptional, can contain information about the actual data of the body (txData), usually the data id, offset and size
txDataoptional, the actual body of the packet
Returns
0 if success, anything else if failure

Definition at line 660 of file com_manager.c.

◆ comManagerSendEnsuredInstance()

int comManagerSendEnsuredInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint8_t  pktInfo,
unsigned char *  data,
unsigned int  dataSize 
)

Definition at line 665 of file com_manager.c.

◆ comManagerSendInstance()

int comManagerSendInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint8_t  pktInfo,
bufPtr_t bodyHdr,
bufPtr_t txData,
uint8_t  pktFlags 
)

Definition at line 639 of file com_manager.c.

◆ comManagerSendRawData()

int comManagerSendRawData ( int  pHandle,
uint32_t  dataId,
void *  dataPtr,
int  dataSize,
int  dataOffset 
)

Convenience function that wraps comManagerSend for sending data structures. Allows arbitrary bytes size, 4 byte multiple not required. No byte swapping occurs.

Parameters
pHandlethe port handle to send data to
dataIdthe data id of the data to send
dataPtrpointer to the data structure to send
dataSizenumber of bytes to send
dataOffsetoffset into dataPtr to send at
Returns
0 if success, anything else if failure

Example:

comManagerSendRawData(0, DID_DEV_INFO, &g_devInfo, sizeof(dev_info_t), 0);

Definition at line 596 of file com_manager.c.

◆ comManagerSendRawDataInstance()

int comManagerSendRawDataInstance ( CMHANDLE  cmInstance,
int  pHandle,
uint32_t  dataId,
void *  dataPtr,
int  dataSize,
int  dataOffset 
)

Definition at line 601 of file com_manager.c.

◆ comManagerSetCallbacks()

void comManagerSetCallbacks ( pfnComManagerAsapMsg  rmcHandler,
pfnComManagerGenMsgHandler  asciiHandler,
pfnComManagerGenMsgHandler  ubloxHandler,
pfnComManagerGenMsgHandler  rtcm3Handler 
)

Register message handler callback functions. Pass in NULL to disable any of these callbacks.

Parameters
msgFunchandler for Realtime Message Controller (RMC) called whenever we get a message broadcast request or message disable command.
msgFunchandler for ASCII messages.
msgFunchandler for ublox messages.
msgFunchandler for RTCM3 messages.

Definition at line 448 of file com_manager.c.

◆ comManagerSetCallbacksInstance()

void comManagerSetCallbacksInstance ( CMHANDLE  cmInstance,
pfnComManagerAsapMsg  rmcHandler,
pfnComManagerGenMsgHandler  asciiHandler,
pfnComManagerGenMsgHandler  ubloxHandler,
pfnComManagerGenMsgHandler  rtcm3Handler 
)

Definition at line 457 of file com_manager.c.

◆ comManagerStep()

void comManagerStep ( void  )

Performs one round of sending and receiving message. This should be called as often as you want to send and receive data.

Definition at line 281 of file com_manager.c.

◆ comManagerStepInstance()

void comManagerStepInstance ( CMHANDLE  cmInstance_)

Definition at line 287 of file com_manager.c.

◆ comManagerStepRxInstance()

void comManagerStepRxInstance ( CMHANDLE  cmInstance)

Definition at line 300 of file com_manager.c.

◆ comManagerStepTxInstance()

void comManagerStepTxInstance ( CMHANDLE  cmInstance)

Definition at line 397 of file com_manager.c.

◆ comManagerValidateBaudRate()

int comManagerValidateBaudRate ( unsigned int  baudRate)

Ensure baudrate is valid for InertialSense hardware

Parameters
baudRatethe baud rate to check
Returns
0 if baud rate is valid, -1 if not

Definition at line 1573 of file com_manager.c.



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