48 size_t lenpre = strlen(pre), lenstr = strlen(str);
49 return lenstr < lenpre ?
false : strncasecmp(pre, str, lenpre) == 0;
52 #define CL_DEFAULT_BAUD_RATE IS_COM_BAUDRATE_DEFAULT 53 #define CL_DEFAULT_COM_PORT "*" 54 #define CL_DEFAULT_DISPLAY_MODE cInertialSenseDisplay::DMODE_PRETTY 55 #define CL_DEFAULT_LOG_TYPE "dat" 56 #define CL_DEFAULT_LOGS_DIRECTORY DEFAULT_LOGS_DIRECTORY 57 #define CL_DEFAULT_ENABLE_LOGGING false 58 #define CL_DEFAULT_MAX_LOG_FILE_SIZE 1024 * 1024 * 5 59 #define CL_DEFAULT_MAX_LOG_SPACE_PERCENT 0.5f 60 #define CL_DEFAULT_REPLAY_SPEED 1.0 61 #define CL_DEFAULT_BOOTLOAD_VERIFY false 94 for (
int i = 1; i < argc; i++)
96 const char* a = argv[i];
103 g_commandLineOptions.
baudRate = strtol(&a[6],
NULL, 10);
107 g_commandLineOptions.
comPort = &a[3];
131 g_commandLineOptions.
host = &a[6];
146 else if (
startsWith(a,
"-log-flush-timeout="))
152 const char* subFolder = &a[5];
153 if (*subFolder ==
'1' ||
startsWith(subFolder,
"true"))
157 else if (*subFolder ==
'\0' || *subFolder ==
'0' ||
startsWith(subFolder,
"false"))
168 g_commandLineOptions.
logPath = &a[4];
172 g_commandLineOptions.
logType = &a[4];
181 g_commandLineOptions.
magRecal =
true;
188 int maxDurationSec = strtol(a + 10,
NULL, 10);
189 if (maxDurationSec > 5)
196 g_commandLineOptions.
streamBaro = (int)atof(&a[9]);
212 g_commandLineOptions.
streamGPS = (int)atof(&a[8]);
220 g_commandLineOptions.
streamIMU1 = (int)atof(&a[9]);
228 g_commandLineOptions.
streamIMU2 = (int)atof(&a[9]);
236 g_commandLineOptions.
streamINS1 = (int)atof(&a[9]);
244 g_commandLineOptions.
streamINS2 = (int)atof(&a[9]);
252 g_commandLineOptions.
streamINS3 = (int)atof(&a[9]);
260 g_commandLineOptions.
streamINS4 = (int)atof(&a[9]);
268 g_commandLineOptions.
streamMag1 = (int)atof(&a[9]);
276 g_commandLineOptions.
streamMag2 = (int)atof(&a[9]);
320 g_commandLineOptions.
streamRTOS = (int)atof(&a[9]);
357 g_commandLineOptions.
logPath = &a[4];
362 g_commandLineOptions.
replaySpeed = (float)atof(&a[4]);
398 cout <<
"Unrecognized command line option: " << a << endl;
412 cout <<
"Use COM_PORT option \"-c=\" with bootloader" << endl;
417 cout <<
"Use COM_PORT option \"-c=\" with bootloader" << endl;
426 if (g_commandLineOptions.
logPath.length() == 0)
428 cout <<
"Please specify the replay log path!" << endl;
435 cout <<
"Failed to load log files: " << g_commandLineOptions.
logPath << endl;
439 cout <<
"Replaying log files: " << g_commandLineOptions.
logPath << endl;
451 cout <<
"Done replaying log files: " << g_commandLineOptions.
logPath << endl;
452 g_inertialSenseDisplay.
Goodbye();
459 cout <<
"-----------------------------------------------------------------" << endl;
462 cout <<
" Command line utility for communicating, logging, and updating" << endl;
463 cout <<
" firmware with Inertial Sense product line." << endl;
469 cout <<
" " <<
APP_NAME <<
APP_EXT <<
" -c=" <<
EXAMPLE_PORT <<
" -baud=115200 -msgINS2 -msgGPS=10 -msgBaro" << boldOff <<
" # stream multiple at 115200 bps, GPS data streamed at 10 times the base period (200ms x 10 = 2 sec)" <<
endlbOn;
474 cout <<
"OPTIONS (General)" << endl;
475 cout <<
" -h --help" << boldOff <<
" display this help menu" <<
endlbOn;
476 cout <<
" -c=" << boldOff <<
"COM_PORT select the serial port. Set COM_PORT to \"*\" for all ports and \"*4\" to use" <<
endlbOn;
477 cout <<
" " << boldOff <<
" only the first four ports. " <<
endlbOn;
479 cout <<
" -magRecal[n]" << boldOff <<
" recalibrate magnetometers: 0=multi-axis, 1=single-axis" <<
endlbOn;
480 cout <<
" -q" << boldOff <<
" quiet mode, no display" <<
endlbOn;
481 cout <<
" -reset " << boldOff <<
" issue software reset. Use caution." <<
endlbOn;
482 cout <<
" -s" << boldOff <<
" scroll displayed messages to show history" <<
endlbOn;
483 cout <<
" -stats" << boldOff <<
" display statistics of data received" <<
endlbOn;
485 cout <<
" -uf=" << boldOff <<
"FILEPATH update firmware using .hex file FILEPATH. Add -baud=115200 for systems w/ baud rate limits." <<
endlbOn;
486 cout <<
" -ub=" << boldOff <<
"BLFILEPATH update bootloader using .bin file BLFILEPATH. Combine with -b option to check version and updated if needed." <<
endlbOn;
487 cout <<
" -uv" << boldOff <<
" verify after firmware update." <<
endlbOn;
490 cout <<
"OPTIONS (Message Streaming)" << endl;
491 cout <<
" -msgPresetPPD " << boldOff <<
" stream preset: post processing data sets" <<
endlbOn;
492 cout <<
" -msgPresetINS2" << boldOff <<
" stream preset: INS2 sets" <<
endlbOn;
493 cout <<
" -msgINS[n] * " << boldOff <<
" stream DID_INS_[n], where [n] = 1, 2, 3 or 4 (without brackets)" <<
endlbOn;
494 cout <<
" -msgDualIMU * " << boldOff <<
" stream DID_DUAL_IMU" <<
endlbOn;
495 cout <<
" -msgPIMU " << boldOff <<
" stream DID_PREINTEGRATED_IMU" <<
endlbOn;
496 cout <<
" -msgMag[n] * " << boldOff <<
" stream DID_MAGNETOMETER_[n], where [n] = 1 or 2 (without brackets)" <<
endlbOn;
497 cout <<
" -msgBaro * " << boldOff <<
" stream DID_BAROMETER" <<
endlbOn;
498 cout <<
" -msgGPS * " << boldOff <<
" stream DID_GPS_NAV" <<
endlbOn;
499 cout <<
" -msgSensors * " << boldOff <<
" stream DID_SYS_SENSORS" <<
endlbOn;
500 cout <<
" -msgRtkPos * " << boldOff <<
" stream DID_GPS1_RTK_POS" <<
endlbOn;
501 cout <<
" -msgRtkPosRel *" << boldOff <<
" stream DID_GPS1_RTK_POS_REL" <<
endlbOn;
502 cout <<
" -msgRtkCmpRel *" << boldOff <<
" stream DID_GPS2_RTK_CMP_REL" <<
endlbOn;
503 cout <<
" -persistent " << boldOff <<
" save current streams as persistent messages enabled on startup" <<
endlbOn;
504 cout <<
" * Message can be appended with =<PERIODMULTIPLE> to change message frequency. Period is then equal to message" <<
endlbOn;
505 cout <<
" source times the PERIODMULTIPLE. If not appended the data will stream at a default rate." <<
endlbOn;
506 cout <<
" Example: -msgINS2=10 will stream data at startupNavDtMs x 10" <<
endlbOn;
508 cout <<
"OPTIONS (Logging to file, disabled by default)" << endl;
509 cout <<
" -lon" << boldOff <<
" enable logging" <<
endlbOn;
510 cout <<
" -lt=" << boldOff <<
"TYPE log type dat (default), sdat, kml or csv" <<
endlbOn;
514 cout <<
" -lts=" << boldOff <<
"0 log sub folder, 0 or blank for none, 1 for timestamp, else use as is" <<
endlbOn;
515 cout <<
" -r" << boldOff <<
" replay data log from default path" <<
endlbOn;
516 cout <<
" -rp=" << boldOff <<
"PATH replay data log from PATH" <<
endlbOn;
517 cout <<
" -rs=" << boldOff <<
"SPEED replay data log at x SPEED. SPEED=0 runs as fast as possible." <<
endlbOn;
519 cout <<
"OPTIONS (Read or write flash configuration)" << endl;
520 cout <<
" -flashConfig" << boldOff <<
" list all \"keys\" and \"values\"" <<
endlbOn;
521 cout <<
" \"-flashConfig=key=value|key=value\" " << boldOff <<
endlbOn;
522 cout <<
" -evbFlashConfig" << boldOff <<
" list all \"keys\" and \"values\"" <<
endlbOn;
523 cout <<
" \"-evbFlashConfig=key=value|key=value\" " << boldOff <<
endlbOn;
524 cout <<
" " << boldOff <<
" set key / value pairs in flash config. Surround with \"quotes\" when using pipe operator." <<
endlbOn;
529 cout <<
"OPTIONS (Client / Server)" << endl;
530 cout <<
" -svr=" << boldOff <<
"INFO used to retrieve external data and send to the uINS. Examples:" << endl;
531 cout <<
" - SERIAL: -svr=RTCM3:SERIAL:" <<
EXAMPLE_PORT <<
":57600 (port, baud rate)" << endl;
532 cout <<
" - RTCM3: -svr=RTCM3:192.168.1.100:7777:URL:user:password" << endl;
533 cout <<
" (URL, user, password optional)" << endl;
534 cout <<
" - UBLOX data: -svr=UBLOX:192.168.1.100:7777 (no URL, user or password)" << endl;
535 cout <<
" - InertialSense: -svr=IS:192.168.1.100:7777 (no URL, user or password)" <<
endlbOn;
536 cout <<
" -host=" << boldOff <<
"IP:PORT used to host a TCP/IP InertialSense server. Examples:" << endl;
537 cout <<
" -host=:7777 (IP is optional)" << endl;
538 cout <<
" -host=192.168.1.43:7777" << endl;
553 if (flashConfigString.length() < 2)
557 cout <<
"Current flash config" << endl;
558 for (map_name_to_info_t::const_iterator i = flashMap.begin(); i != flashMap.end(); i++)
562 cout << i->second.name <<
" = " << stringBuffer << endl;
569 vector<string> keyValues;
571 for (
size_t i = 0; i < keyValues.size(); i++)
573 vector<string> keyAndValue;
575 if (keyAndValue.size() == 2)
577 if (flashMap.find(keyAndValue[0]) == flashMap.end())
579 cout <<
"Unrecognized flash config key '" << keyAndValue[0] <<
"' specified, ignoring." << endl;
583 const data_info_t& info = flashMap.at(keyAndValue[0]);
584 int radix = (keyAndValue[1].compare(0, 2,
"0x") == 0 ? 16 : 10);
585 int substrIndex = 2 * (radix == 16);
586 const string& str = keyAndValue[1].substr(substrIndex);
588 cout <<
"Updated flash config key '" << keyAndValue[0] <<
"' to '" << keyAndValue[1].c_str() <<
"'" << endl;
593 g_inertialSenseDisplay.
Clear();
603 if (flashConfigString.length() < 2)
607 cout <<
"Current EVB flash config" << endl;
608 for (map_name_to_info_t::const_iterator i = flashMap.begin(); i != flashMap.end(); i++)
612 cout << i->second.name <<
" = " << stringBuffer << endl;
619 vector<string> keyValues;
621 for (
size_t i = 0; i < keyValues.size(); i++)
623 vector<string> keyAndValue;
625 if (keyAndValue.size() == 2)
627 if (flashMap.find(keyAndValue[0]) == flashMap.end())
629 cout <<
"Unrecognized EVB flash config key '" << keyAndValue[0] <<
"' specified, ignoring." << endl;
633 const data_info_t& info = flashMap.at(keyAndValue[0]);
634 int radix = (keyAndValue[1].compare(0, 2,
"0x") == 0 ? 16 : 10);
635 int substrIndex = 2 * (radix == 16);
636 const string& str = keyAndValue[1].substr(substrIndex);
638 cout <<
"Updated EVB flash config key '" << keyAndValue[0] <<
"' to '" << keyAndValue[1].c_str() <<
"'" << endl;
643 g_inertialSenseDisplay.
Clear();
static const map_name_to_info_t * GetMapInfo(uint32_t dataId)
evb_flash_cfg_t GetEvbFlashConfig(int pHandle=0)
ostream & boldOn(ostream &os)
string updateBootloaderFilename
void ProcessData(p_data_t *data, bool enableReplay=false, double replaySpeedX=1.0)
uint8_t buf[PKT_BUF_SIZE]
ostream & endlbOff(ostream &os)
size_t splitString(const string &s, const string &delimiter, vector< string > &result)
#define RMC_PRESET_INS_BITS
p_data_t * ReadData(unsigned int device=0)
ostream & endlbOn(ostream &os)
void SetEvbFlashConfig(const evb_flash_cfg_t &evbFlashCfg, int pHandle=0)
static bool StringToData(const char *stringBuffer, int stringLength, const p_data_hdr_t *hdr, uint8_t *dataBuffer, const data_info_t &info, int radix=10, bool json=false)
char data_mapping_string_t[IS_DATA_MAPPING_MAX_STRING_LENGTH]
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)
static eLogType ParseLogType(const string &logTypeString)
nvm_flash_cfg_t GetFlashConfig(int pHandle=0)
ostream & boldOff(ostream &os)
bool disableBroadcastsOnClose
void SetFlashConfig(const nvm_flash_cfg_t &flashConfig, int pHandle=0)
string updateAppFirmwareFilename
int serialPortWrite(serial_port_t *serialPort, const unsigned char *buffer, int writeCount)
USBInterfaceDescriptor data
#define DID_EVB_FLASH_CFG
static bool DataToString(const data_info_t &info, const p_data_hdr_t *hdr, const uint8_t *dataBuffer, data_mapping_string_t stringBuffer, bool json=false)
bool LoadFromDirectory(const string &directory, eLogType logType=LOGTYPE_DAT, vector< string > serials={})
static const string g_emptyString
map< string, data_info_t, sCaseInsensitiveCompare > map_name_to_info_t
static string CreateCurrentTimestamp()
uint32_t timeoutFlushLoggerSeconds
#define RMC_PRESET_PPD_BITS