Classes | Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
InertialSense Class Reference

#include <InertialSense.h>

Inheritance diagram for InertialSense:
Inheritance graph
[legend]

Classes

struct  bootloader_result_t
 
struct  com_manager_cpp_state_t
 
struct  is_device_t
 

Public Member Functions

bool BroadcastBinaryData (uint32_t dataId, int periodMultiple, pfnHandleBinaryData callback=NULL)
 
void BroadcastBinaryDataRmcPreset (uint64_t rmcPreset=RMC_PRESET_INS_BITS, uint32_t rmcOptions=0)
 
void Close ()
 
void CloseServerConnection ()
 
bool CreateHost (const string &ipAndPort)
 
uint64_t GetClientServerByteCount ()
 
size_t GetDeviceCount ()
 
const dev_info_t GetDeviceInfo (int pHandle=0)
 
evb_flash_cfg_t GetEvbFlashConfig (int pHandle=0)
 
nvm_flash_cfg_t GetFlashConfig (int pHandle=0)
 
vector< string > GetPorts ()
 
serial_port_tGetSerialPort (int pHandle=0)
 
system_command_t GetSysCmd (int pHandle=0)
 
time_t GetTimeoutFlushLoggerSeconds ()
 
 InertialSense (pfnHandleBinaryData callback=NULL)
 
bool IsOpen ()
 
bool LoggerEnabled ()
 
bool Open (const char *port, int baudRate=IS_COM_BAUDRATE_DEFAULT, bool disableBroadcastsOnClose=false)
 
bool OpenServerConnection (const string &connectionString)
 
void SendData (eDataIDs dataId, uint8_t *data, uint32_t length, uint32_t offset)
 
void SendRawData (eDataIDs dataId, uint8_t *data, uint32_t length=0, uint32_t offset=0)
 
void SetEvbFlashConfig (const evb_flash_cfg_t &evbFlashCfg, int pHandle=0)
 
void SetFlashConfig (const nvm_flash_cfg_t &flashConfig, int pHandle=0)
 
bool SetLoggerEnabled (bool enable, const string &path=cISLogger::g_emptyString, cISLogger::eLogType logType=cISLogger::eLogType::LOGTYPE_DAT, uint64_t rmcPreset=RMC_PRESET_PPD_BITS, float maxDiskSpacePercent=0.5f, uint32_t maxFileSize=1024 *1024 *5, const string &subFolder=cISLogger::g_emptyString)
 
void SetSysCmd (const system_command_t &sysCmd, int pHandle=0)
 
void SetTimeoutFlushLoggerSeconds (time_t timeoutFlushLoggerSeconds)
 
void StopBroadcasts (bool allPorts=true)
 
bool Update ()
 
virtual ~InertialSense ()
 

Static Public Member Functions

static vector< bootloader_result_tBootloadFile (const string &comPort, const string &fileName, const string &bootloaderFileName, int baudRate=IS_BAUD_RATE_BOOTLOADER, pfnBootloadProgress uploadProgress=NULLPTR, pfnBootloadProgress verifyProgress=NULLPTR, pfnBootloadStatus infoProgress=NULLPTR, bool updateBootloader=false)
 
static vector< bootloader_result_tBootloadFile (const string &comPort, const string &fileName, int baudRate=IS_BAUD_RATE_BOOTLOADER, pfnBootloadProgress uploadProgress=NULLPTR, pfnBootloadProgress verifyProgress=NULLPTR, bool updateBootloader=false)
 

Protected Member Functions

void OnClientConnected (cISTcpServer *server, socket_t socket) OVERRIDE
 
void OnClientConnectFailed (cISTcpServer *server) OVERRIDE
 
void OnClientConnecting (cISTcpServer *server) OVERRIDE
 
void OnClientDisconnected (cISTcpServer *server, socket_t socket) OVERRIDE
 
bool OnPacketReceived (const uint8_t *data, uint32_t dataLength)
 
- Protected Member Functions inherited from iISTcpServerDelegate
virtual void OnClientDataReceived (cISTcpServer *server, socket_t socket, uint8_t *data, int dataLength)
 

Private Member Functions

void DisableLogging ()
 
bool EnableLogging (const string &path, cISLogger::eLogType logType, float maxDiskSpacePercent, uint32_t maxFileSize, const string &subFolder)
 
bool HasReceivedResponseFromAllDevices ()
 
bool HasReceivedResponseFromDevice (size_t index)
 
bool OpenSerialPorts (const char *port, int baudRate)
 
void RemoveDevice (size_t index)
 

Static Private Member Functions

static void LoggerThread (void *info)
 
static void StepLogger (InertialSense *i, const p_data_t *data, int pHandle)
 

Private Attributes

char m_clientBuffer [512]
 
int m_clientBufferBytesToSend
 
uint64_t m_clientServerByteCount
 
cISStreamm_clientStream
 
com_manager_init_t m_cmInit
 
com_manager_port_tm_cmPorts
 
InertialSense::com_manager_cpp_state_t m_comManagerState
 
bool m_disableBroadcastsOnClose
 
is_comm_instance_t m_gpComm
 
uint8_t m_gpCommBuffer [PKT_BUF_SIZE]
 
time_t m_lastLogReInit
 
cISLogger m_logger
 
cMutex m_logMutex
 
map< int, vector< p_data_t > > m_logPackets
 
void * m_logThread
 
cISSerialPort m_serialServer
 
cISTcpClient m_tcpClient
 
cISTcpServer m_tcpServer
 

Detailed Description

Inertial Sense C++ interface Note only one instance of this class per process is supported

Definition at line 65 of file InertialSense.h.

Constructor & Destructor Documentation

◆ InertialSense()

InertialSense::InertialSense ( pfnHandleBinaryData  callback = NULL)

Constructor

Parameters
callbackbinary data callback, optional. If specified, ALL BroadcastBinaryData requests will callback to this function.

Definition at line 125 of file InertialSense.cpp.

◆ ~InertialSense()

InertialSense::~InertialSense ( )
virtual

Destructor

Definition at line 146 of file InertialSense.cpp.

Member Function Documentation

◆ BootloadFile() [1/2]

vector< InertialSense::bootloader_result_t > InertialSense::BootloadFile ( const string &  comPort,
const string &  fileName,
const string &  bootloaderFileName,
int  baudRate = IS_BAUD_RATE_BOOTLOADER,
pfnBootloadProgress  uploadProgress = NULLPTR,
pfnBootloadProgress  verifyProgress = NULLPTR,
pfnBootloadStatus  infoProgress = NULLPTR,
bool  updateBootloader = false 
)
static

Bootload a file - if the bootloader fails, the device stays in bootloader mode and you must call BootloadFile again until it succeeds. If the bootloader gets stuck or has any issues, power cycle the device. Please ensure that all other connections to the com port are closed before calling this function.

Parameters
thecom port to bootload, can be comma separated for multiple
fileNamethe path of the file to bootload
baudRatethe baud rate to bootload at
uploadProgressoptional callback for upload progress
verifyProgressoptional callback for verify progress
Returns
ports and errors, error will be empty if success

Definition at line 678 of file InertialSense.cpp.

◆ BootloadFile() [2/2]

vector< InertialSense::bootloader_result_t > InertialSense::BootloadFile ( const string &  comPort,
const string &  fileName,
int  baudRate = IS_BAUD_RATE_BOOTLOADER,
pfnBootloadProgress  uploadProgress = NULLPTR,
pfnBootloadProgress  verifyProgress = NULLPTR,
bool  updateBootloader = false 
)
static

Definition at line 673 of file InertialSense.cpp.

◆ BroadcastBinaryData()

bool InertialSense::BroadcastBinaryData ( uint32_t  dataId,
int  periodMultiple,
pfnHandleBinaryData  callback = NULL 
)

Definition at line 634 of file InertialSense.cpp.

◆ BroadcastBinaryDataRmcPreset()

void InertialSense::BroadcastBinaryDataRmcPreset ( uint64_t  rmcPreset = RMC_PRESET_INS_BITS,
uint32_t  rmcOptions = 0 
)

Enable streaming of predefined set of messages. The default preset, RMC_PRESET_INS_BITS, stream data necessary for post processing.

Parameters
rmcPresetrealtimeMessageController preset

Definition at line 664 of file InertialSense.cpp.

◆ Close()

void InertialSense::Close ( )

Close the connection, logger and free all resources

Definition at line 541 of file InertialSense.cpp.

◆ CloseServerConnection()

void InertialSense::CloseServerConnection ( )

Close any open connection to a server

Definition at line 382 of file InertialSense.cpp.

◆ CreateHost()

bool InertialSense::CreateHost ( const string &  ipAndPort)

Create a host that will stream data from the uINS to connected clients. Open must be called first to connect to the uINS unit.

Parameters
ipAndPortip address followed by colon followed by port. Ip address is optional and can be blank to auto-detect.
Returns
true if success, false if error

Definition at line 390 of file InertialSense.cpp.

◆ DisableLogging()

void InertialSense::DisableLogging ( )
private

Definition at line 171 of file InertialSense.cpp.

◆ EnableLogging()

bool InertialSense::EnableLogging ( const string &  path,
cISLogger::eLogType  logType,
float  maxDiskSpacePercent,
uint32_t  maxFileSize,
const string &  subFolder 
)
private

Definition at line 152 of file InertialSense.cpp.

◆ GetClientServerByteCount()

uint64_t InertialSense::GetClientServerByteCount ( )
inline

Get the number of bytes read or written to/from client or server connections

Returns
byte count

Definition at line 310 of file InertialSense.h.

◆ GetDeviceCount()

size_t InertialSense::GetDeviceCount ( )

Get the number of open devices

Returns
the number of open devices

Definition at line 416 of file InertialSense.cpp.

◆ GetDeviceInfo()

const dev_info_t InertialSense::GetDeviceInfo ( int  pHandle = 0)
inline

Get the device info

Parameters
pHandlethe pHandle to get device info for
Returns
the device info

Definition at line 234 of file InertialSense.h.

◆ GetEvbFlashConfig()

evb_flash_cfg_t InertialSense::GetEvbFlashConfig ( int  pHandle = 0)
inline

Get the EVB flash config, returns the latest flash config read from the uINS flash memory

Parameters
pHandlethe pHandle to get flash config for
Returns
the EVB flash config

Definition at line 283 of file InertialSense.h.

◆ GetFlashConfig()

nvm_flash_cfg_t InertialSense::GetFlashConfig ( int  pHandle = 0)
inline

Get the flash config, returns the latest flash config read from the uINS flash memory

Parameters
pHandlethe pHandle to get flash config for
Returns
the flash config

Definition at line 269 of file InertialSense.h.

◆ GetPorts()

vector< string > InertialSense::GetPorts ( )

Get all open serial port names

Definition at line 557 of file InertialSense.cpp.

◆ GetSerialPort()

serial_port_t* InertialSense::GetSerialPort ( int  pHandle = 0)
inline

Get access to the underlying serial port

Parameters
pHandlethe pHandle to get the serial port for
Returns
the serial port

Definition at line 317 of file InertialSense.h.

◆ GetSysCmd()

system_command_t InertialSense::GetSysCmd ( int  pHandle = 0)
inline

Get current device system command

Parameters
pHandlethe pHandle to get sysCmd for
Returns
current device system command

Definition at line 248 of file InertialSense.h.

◆ GetTimeoutFlushLoggerSeconds()

time_t InertialSense::GetTimeoutFlushLoggerSeconds ( )
inline

Get the timeout flush logger parameter in seconds

Returns
the timeout flush logger parameter in seconds

Definition at line 330 of file InertialSense.h.

◆ HasReceivedResponseFromAllDevices()

bool InertialSense::HasReceivedResponseFromAllDevices ( )
private

Definition at line 193 of file InertialSense.cpp.

◆ HasReceivedResponseFromDevice()

bool InertialSense::HasReceivedResponseFromDevice ( size_t  index)
private

Definition at line 180 of file InertialSense.cpp.

◆ IsOpen()

bool InertialSense::IsOpen ( )

Check if the connection is open

Definition at line 411 of file InertialSense.cpp.

◆ LoggerEnabled()

bool InertialSense::LoggerEnabled ( )
inline

Gets whether logging is enabled

Returns
whether logging is enabled

Definition at line 185 of file InertialSense.h.

◆ LoggerThread()

void InertialSense::LoggerThread ( void *  info)
staticprivate

Definition at line 221 of file InertialSense.cpp.

◆ OnClientConnected()

void InertialSense::OnClientConnected ( cISTcpServer server,
socket_t  socket 
)
protectedvirtual

Executes when a client has connected

Parameters
serverthe server the client connected to
socketthe connected socket

Reimplemented from iISTcpServerDelegate.

Definition at line 778 of file InertialSense.cpp.

◆ OnClientConnectFailed()

void InertialSense::OnClientConnectFailed ( cISTcpServer server)
protectedvirtual

Executes when a client fails to connect

Parameters
serverthe server the client failed to connect to

Reimplemented from iISTcpServerDelegate.

Definition at line 783 of file InertialSense.cpp.

◆ OnClientConnecting()

void InertialSense::OnClientConnecting ( cISTcpServer server)
protectedvirtual

Executes when a client is connecting

Parameters
serverthe server the client socket is connecting to

Reimplemented from iISTcpServerDelegate.

Definition at line 772 of file InertialSense.cpp.

◆ OnClientDisconnected()

void InertialSense::OnClientDisconnected ( cISTcpServer server,
socket_t  socket 
)
protectedvirtual

Executes when a client disconnects

Parameters
serverthe server the client disconnected from
socketthe socket that disconnected

Reimplemented from iISTcpServerDelegate.

Definition at line 788 of file InertialSense.cpp.

◆ OnPacketReceived()

bool InertialSense::OnPacketReceived ( const uint8_t *  data,
uint32_t  dataLength 
)
protected

Definition at line 760 of file InertialSense.cpp.

◆ Open()

bool InertialSense::Open ( const char *  port,
int  baudRate = IS_COM_BAUDRATE_DEFAULT,
bool  disableBroadcastsOnClose = false 
)

Closes any open connection and then opens the device

Parameters
portthe port to open
baudRatethe baud rate to connect with - supported rates are 115200, 230400, 460800, 921600, 2000000, 3000000
disableBroadcastsOnClosewhether to send a stop broadcasts command to all units on Close
Returns
true if opened, false if failure (i.e. baud rate is bad or port fails to open)

Definition at line 282 of file InertialSense.cpp.

◆ OpenSerialPorts()

bool InertialSense::OpenSerialPorts ( const char *  port,
int  baudRate 
)
private

Definition at line 793 of file InertialSense.cpp.

◆ OpenServerConnection()

bool InertialSense::OpenServerConnection ( const string &  connectionString)

Connect to a server and send the data from that server to the uINS. Open must be called first to connect to the uINS unit.

Parameters
connectionStringthe server to connect, this is the data type (RTCM3,IS,UBLOX) followed by a colon followed by connection info (ip:port or serial:baud). This can also be followed by an optional url, user and password, i.e. RTCM3:192.168.1.100:7777:RTCM3_Mount:user:password
Returns
true if connection opened, false if failure

Definition at line 328 of file InertialSense.cpp.

◆ RemoveDevice()

void InertialSense::RemoveDevice ( size_t  index)
private

Definition at line 210 of file InertialSense.cpp.

◆ SendData()

void InertialSense::SendData ( eDataIDs  dataId,
uint8_t *  data,
uint32_t  length,
uint32_t  offset 
)

Send data to the uINS - this is usually only used for advanced or special cases, normally you won't use this method

Parameters
dataIdthe data id of the data to send
datathe data to send
lengthlength of data to send
offsetoffset into data to send at

Definition at line 579 of file InertialSense.cpp.

◆ SendRawData()

void InertialSense::SendRawData ( eDataIDs  dataId,
uint8_t *  data,
uint32_t  length = 0,
uint32_t  offset = 0 
)

Send raw data to the uINS - this is usually only used for advanced or special cases, normally you won't use this method

Parameters
dataIdthe data id of the data to send
datathe data to send
lengthlength of data to send
offsetoffset into data to send at

Definition at line 588 of file InertialSense.cpp.

◆ SetEvbFlashConfig()

void InertialSense::SetEvbFlashConfig ( const evb_flash_cfg_t evbFlashCfg,
int  pHandle = 0 
)

Set the EVB flash config and update flash config on the EVB-2 flash memory

Parameters
evbFlashCfgthe flash config
pHandlethe pHandle to set flash config for

Definition at line 621 of file InertialSense.cpp.

◆ SetFlashConfig()

void InertialSense::SetFlashConfig ( const nvm_flash_cfg_t flashConfig,
int  pHandle = 0 
)

Set the flash config and update flash config on the uINS flash memory

Parameters
flashConfigthe flash config
pHandlethe pHandle to set flash config for

Definition at line 608 of file InertialSense.cpp.

◆ SetLoggerEnabled()

bool InertialSense::SetLoggerEnabled ( bool  enable,
const string &  path = cISLogger::g_emptyString,
cISLogger::eLogType  logType = cISLogger::eLogType::LOGTYPE_DAT,
uint64_t  rmcPreset = RMC_PRESET_PPD_BITS,
float  maxDiskSpacePercent = 0.5f,
uint32_t  maxFileSize = 1024 * 1024 * 5,
const string &  subFolder = cISLogger::g_emptyString 
)

Enable or disable logging - logging is disabled by default

Parameters
enableenable or disable the logger - disabling the logger after enabling it will close it and flush all data to disk
paththe path to write the log files to
logTypethe type of log to write
logSolutiontrue to log solution stream, false otherwise
maxDiskSpacePercentthe max disk space to use in percent of free space (0.0 to 1.0)
maxFileSizethe max file size for each log file in bytes
chunkSizethe max data to keep in RAM before flushing to disk in bytes
subFoldertimestamp sub folder or empty for none
Returns
true if success, false if failure

Definition at line 299 of file InertialSense.cpp.

◆ SetSysCmd()

void InertialSense::SetSysCmd ( const system_command_t sysCmd,
int  pHandle = 0 
)

Set device configuration

Parameters
pHandlethe pHandle to set sysCmd for
sysCmdnew device configuration

Definition at line 596 of file InertialSense.cpp.

◆ SetTimeoutFlushLoggerSeconds()

void InertialSense::SetTimeoutFlushLoggerSeconds ( time_t  timeoutFlushLoggerSeconds)
inline

Set the timeout flush logger parameter in seconds

Parameters
timeoutFlushLoggerSecondsthe timeout flush logger parameter in seconds

Definition at line 336 of file InertialSense.h.

◆ StepLogger()

void InertialSense::StepLogger ( InertialSense i,
const p_data_t data,
int  pHandle 
)
staticprivate

Definition at line 272 of file InertialSense.cpp.

◆ StopBroadcasts()

void InertialSense::StopBroadcasts ( bool  allPorts = true)

Turn off all messages. Current port only if allPorts = false.

Definition at line 567 of file InertialSense.cpp.

◆ Update()

bool InertialSense::Update ( )

Call in a loop to send and receive data. Call at regular intervals as frequently as want to receive data.

Returns
true if updating should continue, false if the process should be shutdown

Definition at line 421 of file InertialSense.cpp.

Member Data Documentation

◆ m_clientBuffer

char InertialSense::m_clientBuffer[512]
private

Definition at line 366 of file InertialSense.h.

◆ m_clientBufferBytesToSend

int InertialSense::m_clientBufferBytesToSend
private

Definition at line 367 of file InertialSense.h.

◆ m_clientServerByteCount

uint64_t InertialSense::m_clientServerByteCount
private

Definition at line 371 of file InertialSense.h.

◆ m_clientStream

cISStream* InertialSense::m_clientStream
private

Definition at line 370 of file InertialSense.h.

◆ m_cmInit

com_manager_init_t InertialSense::m_cmInit
private

Definition at line 373 of file InertialSense.h.

◆ m_cmPorts

com_manager_port_t* InertialSense::m_cmPorts
private

Definition at line 374 of file InertialSense.h.

◆ m_comManagerState

InertialSense::com_manager_cpp_state_t InertialSense::m_comManagerState
private

Definition at line 359 of file InertialSense.h.

◆ m_disableBroadcastsOnClose

bool InertialSense::m_disableBroadcastsOnClose
private

Definition at line 372 of file InertialSense.h.

◆ m_gpComm

is_comm_instance_t InertialSense::m_gpComm
private

Definition at line 375 of file InertialSense.h.

◆ m_gpCommBuffer

uint8_t InertialSense::m_gpCommBuffer[PKT_BUF_SIZE]
private

Definition at line 376 of file InertialSense.h.

◆ m_lastLogReInit

time_t InertialSense::m_lastLogReInit
private

Definition at line 364 of file InertialSense.h.

◆ m_logger

cISLogger InertialSense::m_logger
private

Definition at line 360 of file InertialSense.h.

◆ m_logMutex

cMutex InertialSense::m_logMutex
private

Definition at line 362 of file InertialSense.h.

◆ m_logPackets

map<int, vector<p_data_t> > InertialSense::m_logPackets
private

Definition at line 363 of file InertialSense.h.

◆ m_logThread

void* InertialSense::m_logThread
private

Definition at line 361 of file InertialSense.h.

◆ m_serialServer

cISSerialPort InertialSense::m_serialServer
private

Definition at line 369 of file InertialSense.h.

◆ m_tcpClient

cISTcpClient InertialSense::m_tcpClient
private

Definition at line 365 of file InertialSense.h.

◆ m_tcpServer

cISTcpServer InertialSense::m_tcpServer
private

Definition at line 368 of file InertialSense.h.


The documentation for this class was generated from the following files:


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