MIP SDK  0.0.1
MicroStrain Communications Library for embedded systems
commands_base.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include "descriptors.h"
4 #include "../mip_result.h"
5 
6 #include <stdint.h>
7 #include <stddef.h>
8 #include <stdbool.h>
9 
10 namespace mip {
11 class Serializer;
12 
13 namespace C {
14 struct mip_interface;
15 } // namespace C
16 
17 namespace commands_base {
18 
25 
27 // Descriptors
29 
30 enum
31 {
33 
34  CMD_PING = 0x01,
39  CMD_RESUME = 0x06,
47 
56 };
57 
59 // Shared Type Definitions
61 
63 {
64  uint16_t firmware_version = 0;
65  char model_name[16] = {0};
66  char model_number[16] = {0};
67  char serial_number[16] = {0};
68  char lot_number[16] = {0};
69  char device_options[16] = {0};
70 
71 };
72 void insert(Serializer& serializer, const BaseDeviceInfo& self);
73 void extract(Serializer& serializer, BaseDeviceInfo& self);
74 
75 enum class TimeFormat : uint8_t
76 {
77  GPS = 1,
78 };
79 
80 struct CommandedTestBitsGq7 : Bitfield<CommandedTestBitsGq7>
81 {
82  enum _enumType : uint32_t
83  {
84  NONE = 0x00000000,
85  GENERAL_HARDWARE_FAULT = 0x00000001,
86  GENERAL_FIRMWARE_FAULT = 0x00000002,
87  TIMING_OVERLOAD = 0x00000004,
88  BUFFER_OVERRUN = 0x00000008,
89  RESERVED = 0x000000F0,
90  IPC_IMU_FAULT = 0x00000100,
91  IPC_NAV_FAULT = 0x00000200,
92  IPC_GNSS_FAULT = 0x00000400,
93  COMMS_FAULT = 0x00000800,
94  IMU_ACCEL_FAULT = 0x00001000,
95  IMU_GYRO_FAULT = 0x00002000,
96  IMU_MAG_FAULT = 0x00004000,
97  IMU_PRESS_FAULT = 0x00008000,
98  IMU_RESERVED = 0x00030000,
99  IMU_CAL_ERROR = 0x00040000,
100  IMU_GENERAL_FAULT = 0x00080000,
101  FILT_RESERVED = 0x00300000,
102  FILT_SOLUTION_FAULT = 0x00400000,
103  FILT_GENERAL_FAULT = 0x00800000,
104  GNSS_RECEIVER1_FAULT = 0x01000000,
105  GNSS_ANTENNA1_FAULT = 0x02000000,
106  GNSS_RECEIVER2_FAULT = 0x04000000,
107  GNSS_ANTENNA2_FAULT = 0x08000000,
108  GNSS_RTCM_FAILURE = 0x10000000,
109  GNSS_RTK_FAULT = 0x20000000,
110  GNSS_SOLUTION_FAULT = 0x40000000,
111  GNSS_GENERAL_FAULT = 0x80000000,
112  };
113  uint32_t value = NONE;
114 
116  CommandedTestBitsGq7(int val) : value((uint32_t)val) {}
117  operator uint32_t() const { return value; }
118  CommandedTestBitsGq7& operator=(uint32_t val) { value = val; return *this; }
119  CommandedTestBitsGq7& operator=(int val) { value = val; return *this; }
120  CommandedTestBitsGq7& operator|=(uint32_t val) { return *this = value | val; }
121  CommandedTestBitsGq7& operator&=(uint32_t val) { return *this = value & val; }
122 };
123 
124 
126 // Mip Fields
128 
138 
139 struct Ping
140 {
143 
144  static const bool HAS_FUNCTION_SELECTOR = false;
145 
146 
147 };
148 void insert(Serializer& serializer, const Ping& self);
149 void extract(Serializer& serializer, Ping& self);
150 
163 
164 struct SetIdle
165 {
168 
169  static const bool HAS_FUNCTION_SELECTOR = false;
170 
171 
172 };
173 void insert(Serializer& serializer, const SetIdle& self);
174 void extract(Serializer& serializer, SetIdle& self);
175 
184 
186 {
189 
190  static const bool HAS_FUNCTION_SELECTOR = false;
191 
192 
193  struct Response
194  {
197 
199 
200  };
201 };
202 void insert(Serializer& serializer, const GetDeviceInfo& self);
203 void extract(Serializer& serializer, GetDeviceInfo& self);
204 
205 void insert(Serializer& serializer, const GetDeviceInfo::Response& self);
206 void extract(Serializer& serializer, GetDeviceInfo::Response& self);
207 
208 CmdResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut);
219 
221 {
224 
225  static const bool HAS_FUNCTION_SELECTOR = false;
226 
227 
228  struct Response
229  {
232 
233  uint8_t descriptors_count = 0;
234  uint16_t* descriptors = {nullptr};
235 
236  };
237 };
238 void insert(Serializer& serializer, const GetDeviceDescriptors& self);
239 void extract(Serializer& serializer, GetDeviceDescriptors& self);
240 
241 void insert(Serializer& serializer, const GetDeviceDescriptors::Response& self);
242 void extract(Serializer& serializer, GetDeviceDescriptors::Response& self);
243 
244 CmdResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount);
257 
259 {
262 
263  static const bool HAS_FUNCTION_SELECTOR = false;
264 
265 
266  struct Response
267  {
270 
271  uint32_t result = 0;
272 
273  };
274 };
275 void insert(Serializer& serializer, const BuiltInTest& self);
276 void extract(Serializer& serializer, BuiltInTest& self);
277 
278 void insert(Serializer& serializer, const BuiltInTest::Response& self);
279 void extract(Serializer& serializer, BuiltInTest::Response& self);
280 
281 CmdResult builtInTest(C::mip_interface& device, uint32_t* resultOut);
291 
292 struct Resume
293 {
296 
297  static const bool HAS_FUNCTION_SELECTOR = false;
298 
299 
300 };
301 void insert(Serializer& serializer, const Resume& self);
302 void extract(Serializer& serializer, Resume& self);
303 
315 
317 {
320 
321  static const bool HAS_FUNCTION_SELECTOR = false;
322 
323 
324  struct Response
325  {
328 
329  uint8_t descriptors_count = 0;
330  uint16_t* descriptors = {nullptr};
331 
332  };
333 };
334 void insert(Serializer& serializer, const GetExtendedDescriptors& self);
335 void extract(Serializer& serializer, GetExtendedDescriptors& self);
336 
337 void insert(Serializer& serializer, const GetExtendedDescriptors::Response& self);
338 void extract(Serializer& serializer, GetExtendedDescriptors::Response& self);
339 
340 CmdResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount);
350 
352 {
355 
356  static const bool HAS_FUNCTION_SELECTOR = false;
357 
358 
359  struct Response
360  {
363 
364  uint8_t result[16] = {0};
365 
366  };
367 };
368 void insert(Serializer& serializer, const ContinuousBit& self);
369 void extract(Serializer& serializer, ContinuousBit& self);
370 
371 void insert(Serializer& serializer, const ContinuousBit::Response& self);
372 void extract(Serializer& serializer, ContinuousBit::Response& self);
373 
374 CmdResult continuousBit(C::mip_interface& device, uint8_t* resultOut);
395 
396 struct CommSpeed
397 {
400 
401  static const bool HAS_WRITE_FUNCTION = true;
402  static const bool HAS_READ_FUNCTION = true;
403  static const bool HAS_SAVE_FUNCTION = true;
404  static const bool HAS_LOAD_FUNCTION = true;
405  static const bool HAS_RESET_FUNCTION = true;
406 
407  static const uint32_t ALL_PORTS = 0;
408  FunctionSelector function = static_cast<FunctionSelector>(0);
409  uint8_t port = 0;
410  uint32_t baud = 0;
411 
412  struct Response
413  {
416 
417  uint8_t port = 0;
418  uint32_t baud = 0;
419 
420  };
421 };
422 void insert(Serializer& serializer, const CommSpeed& self);
423 void extract(Serializer& serializer, CommSpeed& self);
424 
425 void insert(Serializer& serializer, const CommSpeed::Response& self);
426 void extract(Serializer& serializer, CommSpeed::Response& self);
427 
428 CmdResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud);
429 CmdResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut);
430 CmdResult saveCommSpeed(C::mip_interface& device, uint8_t port);
431 CmdResult loadCommSpeed(C::mip_interface& device, uint8_t port);
432 CmdResult defaultCommSpeed(C::mip_interface& device, uint8_t port);
442 
444 {
447 
448  static const bool HAS_WRITE_FUNCTION = true;
449  static const bool HAS_READ_FUNCTION = false;
450  static const bool HAS_SAVE_FUNCTION = false;
451  static const bool HAS_LOAD_FUNCTION = false;
452  static const bool HAS_RESET_FUNCTION = false;
453 
454  enum class FieldId : uint8_t
455  {
456  WEEK_NUMBER = 1,
457  TIME_OF_WEEK = 2,
458  };
459 
460  FunctionSelector function = static_cast<FunctionSelector>(0);
461  FieldId field_id = static_cast<FieldId>(0);
462  uint32_t value = 0;
463 
464 };
465 void insert(Serializer& serializer, const GpsTimeUpdate& self);
466 void extract(Serializer& serializer, GpsTimeUpdate& self);
467 
468 CmdResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value);
478 
479 struct SoftReset
480 {
483 
484  static const bool HAS_FUNCTION_SELECTOR = false;
485 
486 
487 };
488 void insert(Serializer& serializer, const SoftReset& self);
489 void extract(Serializer& serializer, SoftReset& self);
490 
494 
499 } // namespace commands_base
500 } // namespace mip
501 
Serialization class.
Definition: serialization.h:145
void extract(Serializer &serializer, BaseDeviceInfo &self)
Definition: commands_base.cpp:47
TimeFormat
Definition: commands_base.hpp:76
void insert(Serializer &serializer, const BaseDeviceInfo &self)
Definition: commands_base.cpp:27
@ CMD_SOFT_RESET
Definition: commands_base.hpp:46
@ REPLY_GPS_CORRELATION_SECONDS
Definition: commands_base.hpp:52
@ REPLY_GET_EXTENDED_DESCRIPTORS
Definition: commands_base.hpp:53
@ CMD_GET_DEVICE_DESCRIPTORS
Definition: commands_base.hpp:37
@ CMD_COMM_SPEED
Definition: commands_base.hpp:42
@ CMD_CONTINUOUS_BIT
Definition: commands_base.hpp:41
@ CMD_SET_TO_IDLE
Definition: commands_base.hpp:35
@ CMD_GET_EXTENDED_DESCRIPTORS
Definition: commands_base.hpp:40
@ DESCRIPTOR_SET
Definition: commands_base.hpp:32
@ REPLY_GPS_CORRELATION_WEEK
Definition: commands_base.hpp:51
@ CMD_RESUME
Definition: commands_base.hpp:39
@ CMD_BUILT_IN_TEST
Definition: commands_base.hpp:38
@ REPLY_COMM_SPEED
Definition: commands_base.hpp:55
@ REPLY_DEVICE_INFO
Definition: commands_base.hpp:48
@ CMD_GPS_TIME_BROADCAST_NEW
Definition: commands_base.hpp:44
@ REPLY_DEVICE_DESCRIPTORS
Definition: commands_base.hpp:49
@ CMD_SYSTEM_TIME
Definition: commands_base.hpp:45
@ CMD_GPS_TIME_BROADCAST
Definition: commands_base.hpp:43
@ REPLY_BUILT_IN_TEST
Definition: commands_base.hpp:50
@ REPLY_CONTINUOUS_BIT
Definition: commands_base.hpp:54
@ CMD_GET_DEVICE_INFO
Definition: commands_base.hpp:36
@ CMD_PING
Definition: commands_base.hpp:34
@ GPS
GPS time, a = week number since 1980, b = time of week in milliseconds.
CmdResult builtInTest(C::mip_interface &device, uint32_t *resultOut)
Definition: commands_base.cpp:212
CmdResult loadCommSpeed(C::mip_interface &device, uint8_t port)
Definition: commands_base.cpp:429
CmdResult defaultCommSpeed(C::mip_interface &device, uint8_t port)
Definition: commands_base.cpp:441
CmdResult writeCommSpeed(C::mip_interface &device, uint8_t port, uint32_t baud)
Definition: commands_base.cpp:376
CmdResult readCommSpeed(C::mip_interface &device, uint8_t port, uint32_t *baudOut)
Definition: commands_base.cpp:390
CmdResult saveCommSpeed(C::mip_interface &device, uint8_t port)
Definition: commands_base.cpp:417
CmdResult continuousBit(C::mip_interface &device, uint8_t *resultOut)
Definition: commands_base.cpp:316
CmdResult getDeviceDescriptors(C::mip_interface &device, uint16_t *descriptorsOut, size_t descriptorsOutMax, uint8_t *descriptorsOutCount)
Definition: commands_base.cpp:170
CmdResult getDeviceInfo(C::mip_interface &device, BaseDeviceInfo *deviceInfoOut)
Definition: commands_base.cpp:125
CmdResult getExtendedDescriptors(C::mip_interface &device, uint16_t *descriptorsOut, size_t descriptorsOutMax, uint8_t *descriptorsOutCount)
Definition: commands_base.cpp:272
CmdResult writeGpsTimeUpdate(C::mip_interface &device, GpsTimeUpdate::FieldId fieldId, uint32_t value)
Definition: commands_base.cpp:478
CmdResult ping(C::mip_interface &device)
Definition: commands_base.cpp:84
CmdResult resume(C::mip_interface &device)
Definition: commands_base.cpp:242
CmdResult setIdle(C::mip_interface &device)
Definition: commands_base.cpp:99
CmdResult softReset(C::mip_interface &device)
Definition: commands_base.cpp:503
struct mip::C::mip_interface mip_interface
State of the interface for communicating with a MIP device.
A collection of C++ classes and functions covering the full mip api.
Definition: commands_3dm.c:11
FunctionSelector
Definition: descriptors.h:102
A dummy struct which is used to mark bitfield objects.
Definition: descriptors.h:95
State of the interface for communicating with a MIP device.
Definition: mip_interface.h:52
Represents the status of a MIP command.
Definition: mip_result.h:67
Definition: commands_base.hpp:63
char model_number[16]
Definition: commands_base.hpp:66
uint16_t firmware_version
Definition: commands_base.hpp:64
char lot_number[16]
Definition: commands_base.hpp:68
char model_name[16]
Definition: commands_base.hpp:65
char serial_number[16]
Definition: commands_base.hpp:67
char device_options[16]
Definition: commands_base.hpp:69
Definition: commands_base.hpp:267
uint32_t result
Definition: commands_base.hpp:271
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:268
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:269
Definition: commands_base.hpp:259
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:263
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:260
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:261
Definition: commands_base.hpp:413
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:415
uint32_t baud
Port baud rate. Must be a supported rate.
Definition: commands_base.hpp:418
uint8_t port
Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to a...
Definition: commands_base.hpp:417
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:414
Definition: commands_base.hpp:397
uint32_t baud
Port baud rate. Must be a supported rate.
Definition: commands_base.hpp:410
static const bool HAS_SAVE_FUNCTION
Definition: commands_base.hpp:403
static const uint32_t ALL_PORTS
Definition: commands_base.hpp:407
static const bool HAS_WRITE_FUNCTION
Definition: commands_base.hpp:401
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:399
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:398
static const bool HAS_LOAD_FUNCTION
Definition: commands_base.hpp:404
static const bool HAS_RESET_FUNCTION
Definition: commands_base.hpp:405
static const bool HAS_READ_FUNCTION
Definition: commands_base.hpp:402
uint8_t port
Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to a...
Definition: commands_base.hpp:409
Definition: commands_base.hpp:81
CommandedTestBitsGq7()
Definition: commands_base.hpp:115
uint32_t value
Definition: commands_base.hpp:113
_enumType
Definition: commands_base.hpp:83
@ GNSS_ANTENNA1_FAULT
Definition: commands_base.hpp:105
@ IMU_ACCEL_FAULT
Definition: commands_base.hpp:94
@ IPC_IMU_FAULT
Definition: commands_base.hpp:90
@ TIMING_OVERLOAD
Definition: commands_base.hpp:87
@ GNSS_SOLUTION_FAULT
Definition: commands_base.hpp:110
@ GNSS_ANTENNA2_FAULT
Definition: commands_base.hpp:107
@ IMU_RESERVED
Definition: commands_base.hpp:98
@ IMU_CAL_ERROR
Definition: commands_base.hpp:99
@ GNSS_RTK_FAULT
Definition: commands_base.hpp:109
@ GNSS_RECEIVER2_FAULT
Definition: commands_base.hpp:106
@ GNSS_GENERAL_FAULT
Definition: commands_base.hpp:111
@ IPC_NAV_FAULT
Definition: commands_base.hpp:91
@ IMU_GENERAL_FAULT
Definition: commands_base.hpp:100
@ GENERAL_HARDWARE_FAULT
Definition: commands_base.hpp:85
@ IMU_MAG_FAULT
Definition: commands_base.hpp:96
@ BUFFER_OVERRUN
Definition: commands_base.hpp:88
@ FILT_RESERVED
Definition: commands_base.hpp:101
@ IMU_GYRO_FAULT
Definition: commands_base.hpp:95
@ COMMS_FAULT
Definition: commands_base.hpp:93
@ IMU_PRESS_FAULT
Definition: commands_base.hpp:97
@ GNSS_RECEIVER1_FAULT
Definition: commands_base.hpp:104
@ GENERAL_FIRMWARE_FAULT
Definition: commands_base.hpp:86
@ IPC_GNSS_FAULT
Definition: commands_base.hpp:92
@ FILT_SOLUTION_FAULT
Definition: commands_base.hpp:102
@ FILT_GENERAL_FAULT
Definition: commands_base.hpp:103
@ NONE
Definition: commands_base.hpp:84
@ RESERVED
Definition: commands_base.hpp:89
@ GNSS_RTCM_FAILURE
Definition: commands_base.hpp:108
CommandedTestBitsGq7 & operator=(int val)
Definition: commands_base.hpp:119
CommandedTestBitsGq7(int val)
Definition: commands_base.hpp:116
CommandedTestBitsGq7 & operator=(uint32_t val)
Definition: commands_base.hpp:118
CommandedTestBitsGq7 & operator|=(uint32_t val)
Definition: commands_base.hpp:120
CommandedTestBitsGq7 & operator&=(uint32_t val)
Definition: commands_base.hpp:121
Definition: commands_base.hpp:360
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:361
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:362
uint8_t result[16]
Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first....
Definition: commands_base.hpp:364
Definition: commands_base.hpp:352
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:353
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:356
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:354
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:230
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:231
uint8_t descriptors_count
Definition: commands_base.hpp:233
uint16_t * descriptors
Definition: commands_base.hpp:234
Definition: commands_base.hpp:221
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:222
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:223
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:225
Definition: commands_base.hpp:194
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:196
BaseDeviceInfo device_info
Definition: commands_base.hpp:198
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:195
Definition: commands_base.hpp:186
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:187
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:188
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:190
uint16_t * descriptors
Definition: commands_base.hpp:330
uint8_t descriptors_count
Definition: commands_base.hpp:329
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:326
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:327
Definition: commands_base.hpp:317
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:321
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:319
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:318
Definition: commands_base.hpp:444
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:446
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:445
static const bool HAS_LOAD_FUNCTION
Definition: commands_base.hpp:451
FieldId field_id
Determines how to interpret value.
Definition: commands_base.hpp:461
static const bool HAS_WRITE_FUNCTION
Definition: commands_base.hpp:448
static const bool HAS_RESET_FUNCTION
Definition: commands_base.hpp:452
FieldId
Definition: commands_base.hpp:455
@ TIME_OF_WEEK
Time of week in seconds.
uint32_t value
Week number or time of week, depending on the field_id.
Definition: commands_base.hpp:462
static const bool HAS_SAVE_FUNCTION
Definition: commands_base.hpp:450
static const bool HAS_READ_FUNCTION
Definition: commands_base.hpp:449
Definition: commands_base.hpp:140
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:144
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:142
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:141
Definition: commands_base.hpp:293
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:295
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:297
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:294
Definition: commands_base.hpp:165
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:166
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:169
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:167
Definition: commands_base.hpp:480
static const bool HAS_FUNCTION_SELECTOR
Definition: commands_base.hpp:484
static const uint8_t FIELD_DESCRIPTOR
Definition: commands_base.hpp:482
static const uint8_t DESCRIPTOR_SET
Definition: commands_base.hpp:481