Autoware.Auto
xsens_common.hpp
Go to the documentation of this file.
1 // Copyright 2018 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
18 
19 #ifndef XSENS_DRIVER__XSENS_COMMON_HPP_
20 #define XSENS_DRIVER__XSENS_COMMON_HPP_
21 
23 #include <cstdint>
24 #include <mutex>
25 #include <numeric>
26 #include <vector>
27 
28 namespace autoware
29 {
32 namespace drivers
33 {
34 namespace xsens_driver
35 {
36 
37 enum class MID : uint8_t
38 {
39  // Error message, 1 data byte
40  ERROR = 0x42,
41 
42  // State MID
43  // Wake up procedure
44  WAKE_UP = 0x3E,
45  // Wake up ack to put device in config mode
46  WAKE_UP_ACK = 0x3F,
47  // Switch to config state
48  GO_TO_CONFIG = 0x30,
49  // Switch to measurement state
50  GO_TO_MEASUREMENT = 0x10,
51  // Reset device
52  RESET = 0x40,
53 
54  // Informational messages
55  // Request device id
56  REQ_DID = 0x00,
57  // DeviceID, 4 bytes: HH HL LH LL
58  DEVICE_ID = 0x01,
59  // Request product code in plain text
60  REQ_PRODUCT_CODE = 0x1C,
61  // Product code (max 20 bytes data)
62  PRODUCT_CODE = 0x1D,
63  // Request hardware version
64  REQ_HARDWARE_VERSION = 0x1E,
65  // Hardware version
66  HARDWARE_VERSION = 0x1F,
67  // Request firmware revision
68  REQ_FW_REV = 0x12,
69  // Firmware revision, 3 bytes: major minor rev
70  FIRMWARE_REV = 0x13,
71 
72  // Device specific messages
73  // Restore factory defaults
74  RESTORE_FACTORY_DEF = 0x0E,
75  // Baudrate, 1 byte
76  SET_BAUDRATE = 0x18,
77  // Run the built-in self test (MTi-1/10/100 series)
78  RUN_SELFTEST = 0x24,
79  // Self test results, 2 bytes
80  SELFTEST_ACK = 0x25,
81  // GNSS platform setting, 2 bytes (only MTi-G-700/710 with FW1.7 or higher)
82  SET_GNSS_PLATFORM = 0x76,
83  // Error mode, 2 bytes, 0000, 0001, 0002, 0003 (default 0001)
84  SET_ERROR_MODE = 0xDA,
85  // Transmit delay (RS485), 2 bytes, number of clock ticks (1/29.4912 MHz)
86  SET_TRANSMIT_DELAY = 0xDC,
87  // Set state of OptionFlags (MTi-1/2/3), 4 + 4 bytes
88  SET_OPTION_FLAGS = 0x48,
89  // Location ID, 2 bytes, arbitrary, default is 0
90  SET_LOCATION_ID = 0x84,
91 
92  // Synchronization messages
93  // Synchronization settings (MTi-1/10/100 series only), N*12 bytes
94  SET_SYNC_SETTINGS = 0x2C,
95 
96  // Configuration messages
97  // Request configuration
98  REQ_CONFIGURATION = 0x0C,
99  // Configuration, 118 bytes
100  CONFIGURATION = 0x0D,
101  // Sampling period (MTi/MTi-G only), 2 bytes
102  SET_PERIOD = 0x04,
103  // Extended output mode (MTi-10/100), 2 bytes, bit 4 for extended UART
104  SET_EXT_OUTPUT_MODE = 0x86,
105  // Output configuration (MTi-1/10/100 series only), N*4 bytes
107  // Configure NMEA data output (MTi-10/100), 2 bytes
108  SET_STRING_OUTPUT_TYPE = 0x8E,
109  // Set sensor of local alignment quaternion
110  SET_ALIGNMENT_ROTATION = 0xEC,
111  // Output mode (MTi/MTi-G only), 2 bytes
112  SET_OUTPUT_MODE = 0xD0,
113  // Output settings (MTi/MTi-G only), 4 bytes
114  SET_OUTPUT_SETTINGS = 0xD2,
115 
116  // Data messages
117  // Request MTData message (for 65535 skip factor)
118  REQ_DATA = 0x34,
119  // Legacy data packet
120  MT_DATA = 0x32,
121  // Newer data packet (MTi-10/100 series only)
122  MT_DATA2 = 0x36,
123 
124  // Filter messages
125  // Reset orientation, 2 bytes
126  RESET_ORIENTATION = 0xA4,
127  // Request or set UTC time from sensor (MTI-G and MTi-10/100 series)
128  SET_UTC_TIME = 0x60,
129  // Set correction ticks to UTC time
130  ADJUST_UTC_TIME = 0xA8,
131  // UTC Time (MTI-G and MTi-10/100 series), 12 bytes
132  UTC_TIME = 0x61,
133  // Request the available XKF scenarios on the device
135  // Available Scenarios
136  AVAILABLE_SCENARIOS = 0x63,
137  // Current XKF scenario, 2 bytes
138  SET_CURRENT_SCENARIO = 0x64,
139  // Magnitude of the gravity used for the sensor fusion mechanism, 4 bytes
140  SET_GRAVITY_MAGNITUDE = 0x66,
141  // Latitude, Longitude and Altitude for local declination and gravity
142  // (MTi-10/100 series only), 24 bytes
143  SET_LAT_LON_ALT = 0x6E,
144  // Initiate No Rotation procedure (not on MTi-G), 2 bytes
145  SET_NO_ROTATION = 0x22,
146  // In-run Compass Calibration (ICC) command, 1 byte
147  ICC_COMMAND = 0x74,
148 };
149 
150 XSENS_DRIVER_PUBLIC MID MID_from_int(uint16_t value);
151 
152 enum class XDIGroup : uint16_t
153 {
154  // Values for the XDI groups.
155  TEMPERATURE = 0x0800,
156  TIMESTAMP = 0x1000,
157  ORIENTATION_DATA = 0x2000,
158  PRESSURE = 0x3000,
159  ACCELERATION = 0x4000,
160  POSITION = 0x5000,
161  GNSS = 0x7000,
162  ANGULAR_VELOCITY = 0x8000,
163  GPS = 0x8800,
164  SENSOR_COMPONENT_READOUT = 0xA000,
165  ANALOG_IN = 0xB000, // deprecated
166  MAGNETIC = 0xC000,
167  VELOCITY = 0xD000,
168  STATUS = 0xE000,
169 };
170 
171 XSENS_DRIVER_PUBLIC XDIGroup XDIGroup_from_int(uint16_t value);
172 
173 enum class GNSS : uint8_t
174 {
175  PVT_DATA = 0x10,
176  SATELLITES_INFO = 0x20,
177 };
178 
179 XSENS_DRIVER_PUBLIC GNSS GNSS_from_int(uint8_t value);
180 
181 } // namespace xsens_driver
182 } // namespace drivers
183 } // namespace autoware
184 
185 #endif // XSENS_DRIVER__XSENS_COMMON_HPP_
GNSS
Definition: xsens_common.hpp:173
XSENS_DRIVER_PUBLIC XDIGroup XDIGroup_from_int(uint16_t value)
Definition: xsens_common.cpp:130
XDIGroup
Definition: xsens_common.hpp:152
MID
Definition: xsens_common.hpp:37
XSENS_DRIVER_PUBLIC GNSS GNSS_from_int(uint8_t value)
Definition: xsens_common.cpp:166
XSENS_DRIVER_PUBLIC MID MID_from_int(uint16_t value)
Definition: xsens_common.cpp:36
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24