cltool_main.cpp
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2021 Inertial Sense, Inc. - http://inertialsense.com
5 
6 Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files(the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions :
7 
8 The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
9 
10 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 /*
14 * main.cpp
15 *
16 * (c) 2014 Inertial Sense, LLC
17 *
18 * The Inertial Sense Command Line Tool (cltool) shows how easy it is to communicate with the uINS, log data, update firmware and more.
19 *
20 * The following keywords are found within this file to identify instructions
21 * for SDK implementation.
22 *
23 * KEYWORD: SDK Implementation
24 * [C++ COMM INSTRUCTION] - C++ binding API - InertialSense class with binary communication
25 * protocol and serial port support for Linux and Windows.
26 * [C COMM INSTRUCTION] - C binding API - Com Manager with binary communication protocol.
27 * [LOGGER INSTRUCTION] - Data logger.
28 * [BOOTLOADER INSTRUCTION] - Firmware update feature.
29 *
30 * This app is designed to be compiled in Linux and Windows. When using MS
31 * Visual Studio IDE, command line arguments can be supplied by right clicking
32 * the project in solution explorer and then selecting properties -> debugging -> command line arguments
33 */
34 
35 // Contains command line parsing and utility functions. Include this in your project to use these utility functions.
36 #include "cltool.h"
37 
38 static bool output_server_bytes(InertialSense* i, const char* prefix = "", const char* suffix = "")
39 {
40  static float serverKBps = 0;
41  static uint64_t serverByteCount = 0;
42  static uint64_t updateCount = 0;
43  static uint64_t serverByteRateTimeMsLast = 0;
44  static uint64_t serverByteCountLast = 0;
45 
47  {
48  uint64_t newServerByteCount = i->GetClientServerByteCount();
49  if (serverByteCount != newServerByteCount)
50  {
51  serverByteCount = newServerByteCount;
52 
53  // Data rate of server bytes
54  uint64_t timeMs = getTickCount();
55  uint64_t dtMs = timeMs - serverByteRateTimeMsLast;
56  if (dtMs >= 1000)
57  {
58  uint64_t serverBytesDelta = serverByteCount - serverByteCountLast;
59  serverKBps = ((float)serverBytesDelta / (float)dtMs);
60 
61  // Update history
62  serverByteCountLast = serverByteCount;
63  serverByteRateTimeMsLast = timeMs;
64  }
65  printf("%sServer: %02" PRIu64 " (%3.1f KB/s : %lld) %s", prefix, (++updateCount) % 100, serverKBps, (long long)i->GetClientServerByteCount(), suffix);
66  return true;
67  }
68  }
69  return false;
70 }
71 
73 {
75  {
76  return;
77  }
78 
80  {
81  char suffix[256];
83  suffix[0] = '\0';
85  {
86  snprintf(suffix, sizeof(suffix), "Com errors: %d ", status->communicationErrorCount);
87  }
89  if (i->GetClientServerByteCount() == 0)
90  {
91  cout << endl << suffix;
92  }
93  else
94  {
95  output_server_bytes(i, "\n", suffix);
96  }
97  }
98 }
99 
100 // [C++ COMM INSTRUCTION] STEP 5: Handle received data
101 static void cltool_dataCallback(InertialSense* i, p_data_t* data, int pHandle)
102 {
103  (void)i;
104  (void)pHandle;
105  // Print data to terminal
108 
109 #if 0
110 
111  // uDatasets is a union of all datasets that we can receive. See data_sets.h for a full list of all available datasets.
112  uDatasets d = {};
113  copyDataPToStructP(&d, data, sizeof(uDatasets));
114 
115  // Example of how to access dataset fields.
116  switch (data->hdr.id)
117  {
118  case DID_INS_2:
119  d.ins2.qn2b; // quaternion attitude
120  d.ins2.uvw; // body velocities
121  d.ins2.lla; // latitude, longitude, altitude
122  break;
123  case DID_INS_1:
124  d.ins1.theta; // euler attitude
125  d.ins1.lla; // latitude, longitude, altitude
126  break;
127  case DID_DUAL_IMU:
128  d.dualImu;
129  break;
130  case DID_PREINTEGRATED_IMU:
131  d.pImu;
132  break;
133  case DID_GPS_NAV:
134  d.gpsNav;
135  break;
136  case DID_MAGNETOMETER_1:
137  d.mag;
138  break;
139  case DID_MAGNETOMETER_2:
140  d.mag;
141  break;
142  case DID_BAROMETER:
143  d.baro;
144  break;
145  case DID_SYS_SENSORS:
146  d.sysSensors;
147  break;
148  }
149 
150 #endif
151 
152 }
153 
154 // Where we tell the uINS what data to send and at what rate.
155 // "cltool_dataCallback()" is registered as the callback functions for all received data.
156 // All DID messages are found in data_sets.h
157 static bool cltool_setupCommunications(InertialSense& inertialSenseInterface)
158 {
159  inertialSenseInterface.StopBroadcasts(); // Stop streaming any prior messages
160 
161  if (g_commandLineOptions.asciiMessages.size() != 0)
162  {
164  return true;
165  }
166 
167  // ask for device info every 2 seconds
168  inertialSenseInterface.BroadcastBinaryData(DID_DEV_INFO, 2000);
169 
170  // depending on command line options. stream various data sets
172  {
174  }
176  {
178  }
180  {
182  }
184  {
186  }
188  {
190  }
192  {
194  }
196  {
198  }
200  {
202  }
204  {
206  }
208  {
210  }
212  {
214  }
216  {
218  }
220  {
222  }
224  {
226  }
228  {
230  system_command_t cfg;
232  cfg.invCommand = ~cfg.command;
233  inertialSenseInterface.SendRawData(DID_SYS_CMD, (uint8_t*)&cfg, sizeof(system_command_t), 0);
234  }
236  {
238  }
240  {
242  }
244  {
246  }
248  {
249  // Enable broadcase of DID_MAG_CAL so we can observe progress and tell when the calibration is done (i.e. DID_MAG_CAL.recalCmd == 100).
250  inertialSenseInterface.BroadcastBinaryData(DID_MAG_CAL, 100);
251  // Enable mag recal
252  inertialSenseInterface.SendRawData(DID_MAG_CAL, (uint8_t*)&g_commandLineOptions.magRecalMode, sizeof(g_commandLineOptions.magRecalMode), offsetof(mag_cal_t, recalCmd));
253  }
255  { // Enable mult-axis
256  inertialSenseInterface.SendRawData(DID_SURVEY_IN, (uint8_t*)&g_commandLineOptions.surveyIn, sizeof(survey_in_t), 0);
257  }
259  {
261  }
263  { // Save persistent messages to flash
264  system_command_t cfg;
266  cfg.invCommand = ~cfg.command;
267  inertialSenseInterface.SendRawData(DID_SYS_CMD, (uint8_t*)&cfg, sizeof(system_command_t), 0);
268  }
270  { // Issue software reset
271  system_command_t cfg;
273  cfg.invCommand = ~cfg.command;
274  inertialSenseInterface.SendRawData(DID_SYS_CMD, (uint8_t*)&cfg, sizeof(system_command_t), 0);
275  }
276 
277  if (g_commandLineOptions.serverConnection.length() != 0)
278  {
279  if (g_commandLineOptions.serverConnection.find("RTCM3:") == 0 ||
280  g_commandLineOptions.serverConnection.find("IS:") == 0 ||
281  g_commandLineOptions.serverConnection.find("UBLOX:") == 0)
282  {
283  if (!inertialSenseInterface.OpenServerConnection(g_commandLineOptions.serverConnection))
284  {
285  cout << "Failed to connect to server." << endl;
286  }
287  }
288  else
289  {
290  cout << "Invalid server connection, must prefix with RTCM3:, IS: or UBLOX:, " << g_commandLineOptions.serverConnection << endl;
291  return false;
292  }
293  }
294  if (g_commandLineOptions.flashConfig.length() != 0)
295  {
296  return cltool_updateFlashConfig(inertialSenseInterface, g_commandLineOptions.flashConfig);
297  }
298  if (g_commandLineOptions.evbFlashConfig.length() != 0)
299  {
300  return cltool_updateEvbFlashConfig(inertialSenseInterface, g_commandLineOptions.evbFlashConfig);
301  }
302  return true;
303 }
304 
306 {
307  // [BOOTLOADER INSTRUCTION] Update firmware
308  cout << "Updating application firmware using file at " << g_commandLineOptions.updateAppFirmwareFilename << endl;
309  vector<InertialSense::bootloader_result_t> results = InertialSense::BootloadFile(g_commandLineOptions.comPort,
316  cout << endl << "Results:" << endl;
317  int errorCount = 0;
318  for (size_t i = 0; i < results.size(); i++)
319  {
320  cout << results[i].port << ": " << (results[i].error.size() == 0 ? "Success\n" : results[i].error);
321  errorCount += (int)(results[i].error.size() != 0);
322  }
323  if (errorCount != 0)
324  {
325  cout << endl << errorCount << " ports failed." << endl;
326  }
327  return (errorCount == 0 ? 0 : -1);
328 }
329 
331 {
332  cout << "Updating bootloader using file at " << g_commandLineOptions.updateBootloaderFilename << endl;
333  vector<InertialSense::bootloader_result_t> results = InertialSense::BootloadFile(g_commandLineOptions.comPort,
335  "",
340  true);
341  cout << endl << "Results:" << endl;
342  int errorCount = 0;
343  for (size_t i = 0; i < results.size(); i++)
344  {
345  cout << results[i].port << ": " << (results[i].error.size() == 0 ? "Success\n" : results[i].error);
346  errorCount += (int)(results[i].error.size() != 0);
347  }
348  if (errorCount != 0)
349  {
350  cout << endl << errorCount << " ports failed." << endl;
351  }
352  return (errorCount == 0 ? 0 : -1);
353 }
354 
355 static int cltool_createHost()
356 {
357  InertialSense inertialSenseInterface;
358  if (!inertialSenseInterface.Open(g_commandLineOptions.comPort.c_str(), g_commandLineOptions.baudRate))
359  {
360  cout << "Failed to open serial port at " << g_commandLineOptions.comPort.c_str() << endl;
361  return -1;
362  }
363  else if (g_commandLineOptions.flashConfig.length() != 0 && !cltool_updateFlashConfig(inertialSenseInterface, g_commandLineOptions.flashConfig))
364  {
365  cout << "Failed to update flash config" << endl;
366  return -1;
367  }
368  else if (g_commandLineOptions.evbFlashConfig.length() != 0 && !cltool_updateFlashConfig(inertialSenseInterface, g_commandLineOptions.evbFlashConfig))
369  {
370  cout << "Failed to update EVB flash config" << endl;
371  return -1;
372  }
373  else if (!inertialSenseInterface.CreateHost(g_commandLineOptions.host))
374  {
375  cout << "Failed to create host at " << g_commandLineOptions.host << endl;
376  return -1;
377  }
378 
379  inertialSenseInterface.StopBroadcasts();
380 
382  {
383  inertialSenseInterface.Update();
385  output_server_bytes(&inertialSenseInterface);
386  }
387  cout << "Shutting down..." << endl;
388 
389  // close the interface cleanly, this ensures serial port and any logging are shutdown properly
390  inertialSenseInterface.Close();
391 
392  return 0;
393 }
394 
395 static int inertialSenseMain()
396 {
397  // clear display
400 
401  // if replay data log specified on command line, do that now and return
403  {
404  // [REPLAY INSTRUCTION] 1.) Replay data log
405  return !cltool_replayDataLog();
406  }
407  // if app firmware was specified on the command line, do that now and return
408  else if (g_commandLineOptions.updateAppFirmwareFilename.length() != 0)
409  {
411  {
412  cout << "Incorrect file extension." << endl;
413  return -1;
414  }
415 
416  // [BOOTLOADER INSTRUCTION] 1.) Run bootloader
417  return cltool_updateAppFirmware();
418  }
419  // if bootloader filename was specified on the command line, do that now and return
420  else if (g_commandLineOptions.updateBootloaderFilename.length() != 0)
421  {
423  {
424  cout << "Incorrect file extension." << endl;
425  return -1;
426  }
427 
428  return cltool_updateBootloader();
429  }
430  // if host was specified on the command line, create a tcp server
431  else if (g_commandLineOptions.host.length() != 0)
432  {
433  return cltool_createHost();
434  }
435  else if (g_commandLineOptions.asciiMessages.size() != 0)
436  {
437  serial_port_t serialForAscii;
438  serialPortPlatformInit(&serialForAscii);
440  serialPortWriteAscii(&serialForAscii, "STPB", 4);
441  serialPortWriteAscii(&serialForAscii, ("ASCB," + g_commandLineOptions.asciiMessages).c_str(), (int)(5 + g_commandLineOptions.asciiMessages.size()));
442  unsigned char line[512];
443  unsigned char* asciiData;
445  {
446  int count = serialPortReadAsciiTimeout(&serialForAscii, line, sizeof(line), 100, &asciiData);
447  if (count > 0)
448  {
449  printf("%s", (char*)asciiData);
450  printf("\r\n");
451  }
452  }
453  }
454  // open the device, start streaming data and logging if needed
455  else
456  {
457  // [C++ COMM INSTRUCTION] STEP 1: Instantiate InertialSense Class
458  // Create InertialSense object, passing in data callback function pointer.
459  InertialSense inertialSenseInterface(cltool_dataCallback);
460 
461  // [C++ COMM INSTRUCTION] STEP 2: Open serial port
463  {
464  cout << "Failed to open serial port at " << g_commandLineOptions.comPort.c_str() << endl;
465  return -1; // Failed to open serial port
466  }
467 
468  // [C++ COMM INSTRUCTION] STEP 3: Enable data broadcasting
469  if (cltool_setupCommunications(inertialSenseInterface))
470  {
471  // [LOGGER INSTRUCTION] Setup and start data logger
472  if (g_commandLineOptions.asciiMessages.size() == 0 && !cltool_setupLogger(inertialSenseInterface))
473  {
474  cout << "Failed to setup logger!" << endl;
475  inertialSenseInterface.Close();
476  return -1;
477  }
478  try
479  {
480  // Main loop. Could be in separate thread if desired.
482  {
483  // [C++ COMM INSTRUCTION] STEP 4: Read data
484  if (!inertialSenseInterface.Update())
485  {
486  // device disconnected, exit
487  break;
488  }
489  }
490  }
491  catch (...)
492  {
493  cout << "Unknown exception...";
494  }
495  }
496 
497  cout << "Shutting down..." << endl;
498 
499  // [C++ COMM INSTRUCTION] STEP 6: Close interface
500  // Close cleanly to ensure serial port and logging are shutdown properly. (optional)
501  inertialSenseInterface.Close();
502  }
503 
504  return 0;
505 }
506 
507 
508 int cltool_main(int argc, char* argv[])
509 {
510  // Parse command line options
511  if (!cltool_parseCommandLine(argc, argv))
512  {
514 
515  // parsing failed
516  return -1;
517  }
518 
519  // InertialSense class example using command line options
520  int result = inertialSenseMain();
521  if (result == -1)
522  {
524 
525  // Pause so user can read error
526  SLEEP_MS(2000);
527  }
528 
530 
531  return result;
532 }
d
#define DID_SURVEY_IN
Definition: data_sets.h:107
string asciiMessages
Definition: cltool.h:60
#define DID_DUAL_IMU
Definition: data_sets.h:92
int streamRtkCmpRel
Definition: cltool.h:76
void StopBroadcasts(bool allPorts=true)
static vector< bootloader_result_t > 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)
ins_2_t ins2
Definition: data_sets.h:3529
static int cltool_updateBootloader()
com_manager_status_t * comManagerGetStatus(int pHandle)
Definition: com_manager.c:487
bool bootloaderVerify
Definition: cltool.h:54
int serialPortOpen(serial_port_t *serialPort, const char *port, int baudRate, int blocking)
Definition: serialPort.c:28
float qn2b[4]
Definition: data_sets.h:534
bool cltool_updateEvbFlashConfig(InertialSense &inertialSenseInterface, string flashConfigString)
Definition: cltool.cpp:598
ins_1_t ins1
Definition: data_sets.h:3528
string updateBootloaderFilename
Definition: cltool.h:53
void ProcessData(p_data_t *data, bool enableReplay=false, double replaySpeedX=1.0)
Definition: ISDisplay.cpp:283
static int cltool_updateAppFirmware()
uint32_t id
Definition: ISComm.h:376
is_can_uvw uvw
Definition: CAN_comm.h:257
#define DID_INS_1
Definition: data_sets.h:38
int streamRtkPosRel
Definition: cltool.h:75
static void output_client_bytes(InertialSense *i)
Definition: cltool_main.cpp:72
uint32_t state
Definition: data_sets.h:2963
#define DID_GPS2_RTK_CMP_REL
Definition: data_sets.h:125
uint32_t communicationErrorCount
Definition: com_manager.h:89
cInertialSenseDisplay g_inertialSenseDisplay
Definition: cltool.cpp:18
bool OpenServerConnection(const string &connectionString)
uint64_t GetClientServerByteCount()
bool cltool_replayDataLog()
Definition: cltool.cpp:424
float mag[3]
Definition: data_sets.h:655
size_t count(InputIterator first, InputIterator last, T const &item)
Definition: catch.hpp:3206
#define DID_DEV_INFO
Definition: data_sets.h:35
bool softwareReset
Definition: cltool.h:56
#define DID_INS_2
Definition: data_sets.h:39
int bootloadUploadProgress(const void *port, float percent)
cmd_options_t g_commandLineOptions
Definition: cltool.cpp:16
int bootloadVerifyProgress(const void *port, float percent)
int streamRTOS
Definition: cltool.h:82
char copyDataPToStructP(void *sptr, const p_data_t *data, const unsigned int maxsize)
Definition: ISComm.c:975
void SetTimeoutFlushLoggerSeconds(time_t timeoutFlushLoggerSeconds)
uint64_t getTickCount(void)
int serialPortPlatformInit(serial_port_t *serialPort)
#define DID_PREINTEGRATED_IMU
Definition: data_sets.h:37
#define SLEEP_MS(timeMs)
Definition: ISUtilities.h:134
int baudRate
Definition: cltool.h:92
void SetDisplayMode(eDisplayMode mode)
Definition: ISDisplay.h:43
int streamSensorsADC
Definition: cltool.h:83
bool cltool_parseCommandLine(int argc, char *argv[])
Definition: cltool.cpp:63
#define DID_MAG_CAL
Definition: data_sets.h:53
#define NULLPTR
Definition: ISConstants.h:426
#define RMC_OPTIONS_PRESERVE_CTRL
Definition: data_sets.h:1275
bool persistentMessages
Definition: cltool.h:65
bool CreateHost(const string &ipAndPort)
void bootloadStatusInfo(const void *port, const char *str)
bool cltool_setupLogger(InertialSense &inertialSenseInterface)
Definition: cltool.cpp:27
#define DID_MAGNETOMETER_2
Definition: data_sets.h:89
int streamINS2
Definition: cltool.h:67
std::ostream & cout()
uint32_t invCommand
Definition: data_sets.h:1125
void SendRawData(eDataIDs dataId, uint8_t *data, uint32_t length=0, uint32_t offset=0)
string evbFlashConfig
Definition: cltool.h:99
bool magRecal
Definition: cltool.h:57
bool cltool_updateFlashConfig(InertialSense &inertialSenseInterface, string flashConfigString)
Definition: cltool.cpp:548
#define printf(...)
Definition: evb_tasks.h:36
preintegrated_imu_t pImu
Definition: data_sets.h:3539
#define DID_SYS_CMD
Definition: data_sets.h:41
bool disableBroadcastsOnClose
Definition: cltool.h:93
uint32_t command
Definition: data_sets.h:1122
string updateAppFirmwareFilename
Definition: cltool.h:52
int streamGPS
Definition: cltool.h:73
int cltool_main(int argc, char *argv[])
int streamDThetaVel
Definition: cltool.h:81
int streamSysSensors
Definition: cltool.h:80
survey_in_t surveyIn
Definition: cltool.h:59
int streamRtkPos
Definition: cltool.h:74
uint64_t rmcPreset
Definition: cltool.h:64
double lla[3]
Definition: data_sets.h:511
int streamMag1
Definition: cltool.h:77
static bool cltool_setupCommunications(InertialSense &inertialSenseInterface)
string comPort
Definition: cltool.h:51
int displayMode
Definition: cltool.h:62
p_data_hdr_t hdr
Definition: ISComm.h:389
int streamDualIMU
Definition: cltool.h:70
int serialPortReadAsciiTimeout(serial_port_t *serialPort, unsigned char *buffer, int bufferLength, int timeoutMilliseconds, unsigned char **asciiData)
Definition: serialPort.c:150
sys_sensors_t sysSensors
Definition: data_sets.h:3550
#define DID_MAGNETOMETER_1
Definition: data_sets.h:86
int streamBaro
Definition: cltool.h:79
USBInterfaceDescriptor data
bool BroadcastBinaryData(uint32_t dataId, int periodMultiple, pfnHandleBinaryData callback=NULL)
string flashConfig
Definition: cltool.h:98
#define DID_GPS1_POS
Definition: data_sets.h:47
float theta[3]
Definition: data_sets.h:505
#define DID_SYS_SENSORS
Definition: data_sets.h:45
#define DID_INS_3
Definition: data_sets.h:99
uint32_t magRecalMode
Definition: cltool.h:58
eDisplayMode GetDisplayMode()
Definition: ISDisplay.h:44
bool Open(const char *port, int baudRate=IS_COM_BAUDRATE_DEFAULT, bool disableBroadcastsOnClose=false)
#define snprintf
Definition: test_suite.cpp:86
barometer_t baro
Definition: data_sets.h:3536
int streamINS4
Definition: cltool.h:69
serial_port_t * GetSerialPort(int pHandle=0)
static void cltool_dataCallback(InertialSense *i, p_data_t *data, int pHandle)
#define DID_WHEEL_ENCODER
Definition: data_sets.h:105
#define DID_GPS1_RTK_POS
Definition: data_sets.h:88
#define DID_GPS1_RTK_POS_REL
Definition: data_sets.h:55
int streamINS3
Definition: cltool.h:68
uint32_t timeoutFlushLoggerSeconds
Definition: cltool.h:101
int serialPortWriteAscii(serial_port_t *serialPort, const char *buffer, int bufferLength)
Definition: serialPort.c:230
bool replayDataLog
Definition: cltool.h:55
static bool output_server_bytes(InertialSense *i, const char *prefix="", const char *suffix="")
Definition: cltool_main.cpp:38
int streamWheelEncoder
Definition: cltool.h:84
string host
Definition: cltool.h:96
static int inertialSenseMain()
void cltool_outputHelp()
Definition: cltool.cpp:543
#define DID_INS_4
Definition: data_sets.h:100
static int cltool_createHost()
#define DID_BAROMETER
Definition: data_sets.h:87
string serverConnection
Definition: cltool.h:95
#define DID_RTOS_INFO
Definition: data_sets.h:72
int streamMag2
Definition: cltool.h:78
void BroadcastBinaryDataRmcPreset(uint64_t rmcPreset=RMC_PRESET_INS_BITS, uint32_t rmcOptions=0)
dual_imu_t dualImu
Definition: data_sets.h:3533
int streamINS1
Definition: cltool.h:66
#define DID_SENSORS_ADC
Definition: data_sets.h:62


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