sl_lidar_cmd.h
Go to the documentation of this file.
1 /*
2 * Slamtec LIDAR SDK
3 *
4 * sl_lidar_cmd.h
5 *
6 * Copyright (c) 2020 Shanghai Slamtec Co., Ltd.
7 */
8 
9 /*
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions are met:
12  *
13  * 1. Redistributions of source code must retain the above copyright notice,
14  * this list of conditions and the following disclaimer.
15  *
16  * 2. Redistributions in binary form must reproduce the above copyright notice,
17  * this list of conditions and the following disclaimer in the documentation
18  * and/or other materials provided with the distribution.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
22  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
23  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
24  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
25  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
26  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
27  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
28  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
29  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
30  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *
32  */
33 
34 #pragma once
35 
36 #if defined(_MSC_VER)
37 #pragma warning(push)
38 #pragma warning(disable:4200)
39 #endif
40 
41 #include "sl_lidar_protocol.h"
42 
43  // Commands
44  //-----------------------------------------
45 
46 
47 #define SL_LIDAR_AUTOBAUD_MAGICBYTE 0x41
48 
49  // Commands without payload and response
50 #define SL_LIDAR_CMD_STOP 0x25
51 #define SL_LIDAR_CMD_SCAN 0x20
52 #define SL_LIDAR_CMD_FORCE_SCAN 0x21
53 #define SL_LIDAR_CMD_RESET 0x40
54 
55 // Commands with payload but no response
56 #define SL_LIDAR_CMD_NEW_BAUDRATE_CONFIRM 0x90 //added in fw 1.30
57 
58 // Commands without payload but have response
59 #define SL_LIDAR_CMD_GET_DEVICE_INFO 0x50
60 #define SL_LIDAR_CMD_GET_DEVICE_HEALTH 0x52
61 
62 #define SL_LIDAR_CMD_GET_SAMPLERATE 0x59 //added in fw 1.17
63 
64 #define SL_LIDAR_CMD_HQ_MOTOR_SPEED_CTRL 0xA8
65 
66 
67 // Commands with payload and have response
68 #define SL_LIDAR_CMD_EXPRESS_SCAN 0x82 //added in fw 1.17
69 #define SL_LIDAR_CMD_HQ_SCAN 0x83 //added in fw 1.24
70 #define SL_LIDAR_CMD_GET_LIDAR_CONF 0x84 //added in fw 1.24
71 #define SL_LIDAR_CMD_SET_LIDAR_CONF 0x85 //added in fw 1.24
72 //add for A2 to set RPLIDAR motor pwm when using accessory board
73 #define SL_LIDAR_CMD_SET_MOTOR_PWM 0xF0
74 #define SL_LIDAR_CMD_GET_ACC_BOARD_FLAG 0xFF
75 
76 #if defined(_WIN32)
77 #pragma pack(1)
78 #endif
79 
80 
81 // Payloads
82 // ------------------------------------------
83 #define SL_LIDAR_EXPRESS_SCAN_MODE_NORMAL 0
84 #define SL_LIDAR_EXPRESS_SCAN_MODE_FIXANGLE 0 // won't been supported but keep to prevent build fail
85 //for express working flag(extending express scan protocol)
86 #define SL_LIDAR_EXPRESS_SCAN_FLAG_BOOST 0x0001
87 #define SL_LIDAR_EXPRESS_SCAN_FLAG_SUNLIGHT_REJECTION 0x0002
88 
89 //for ultra express working flag
90 #define SL_LIDAR_ULTRAEXPRESS_SCAN_FLAG_STD 0x0001
91 #define SL_LIDAR_ULTRAEXPRESS_SCAN_FLAG_HIGH_SENSITIVITY 0x0002
92 
94 {
95  sl_u8 working_mode;
96  sl_u16 working_flags;
97  sl_u16 param;
98 } __attribute__((packed)) sl_lidar_payload_express_scan_t;
99 
101 {
102  sl_u8 flag;
103  sl_u8 reserved[32];
104 } __attribute__((packed)) sl_lidar_payload_hq_scan_t;
105 
107 {
108  sl_u32 type;
109 } __attribute__((packed)) sl_lidar_payload_get_scan_conf_t;
110 
112  sl_u32 type;
113 } __attribute__((packed)) sl_lidar_payload_set_scan_conf_t;
114 
115 
116 #define DEFAULT_MOTOR_SPEED (0xFFFFu)
117 
119 {
120  sl_u16 pwm_value;
121 } __attribute__((packed)) sl_lidar_payload_motor_pwm_t;
122 
124 {
125  sl_u32 reserved;
126 } __attribute__((packed)) sl_lidar_payload_acc_board_flag_t;
127 
129  sl_u16 rpm;
130 } __attribute__((packed))sl_lidar_payload_hq_spd_ctrl_t;
131 
132 
134  sl_u16 flag; // reserved, must be 0x5F5F
135  sl_u32 required_bps;
136  sl_u16 param;
137 } __attribute__((packed)) sl_lidar_payload_new_bps_confirmation_t;
138 
139 // Response
140 // ------------------------------------------
141 #define SL_LIDAR_ANS_TYPE_DEVINFO 0x4
142 #define SL_LIDAR_ANS_TYPE_DEVHEALTH 0x6
143 
144 #define SL_LIDAR_ANS_TYPE_MEASUREMENT 0x81
145 // Added in FW ver 1.17
146 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_CAPSULED 0x82
147 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_HQ 0x83
148 //added in FW ver 1.23alpha
149 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_CAPSULED_ULTRA 0x84
150 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED 0x85
151 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_ULTRA_DENSE_CAPSULED 0x86
152 
153 
154 // Added in FW ver 1.17
155 #define SL_LIDAR_ANS_TYPE_SAMPLE_RATE 0x15
156 
157 //added in FW ver 1.24
158 #define SL_LIDAR_ANS_TYPE_GET_LIDAR_CONF 0x20
159 #define SL_LIDAR_ANS_TYPE_SET_LIDAR_CONF 0x21
160 
161 
162 #define SL_LIDAR_ANS_TYPE_ACC_BOARD_FLAG 0xFF
163 
164 #define SL_LIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK (0x1)
166 {
167  sl_u32 support_flag;
168 } __attribute__((packed)) sl_lidar_response_acc_board_flag_t;
169 
170 
171 #define SL_LIDAR_STATUS_OK 0x0
172 #define SL_LIDAR_STATUS_WARNING 0x1
173 #define SL_LIDAR_STATUS_ERROR 0x2
174 
175 #define SL_LIDAR_RESP_MEASUREMENT_SYNCBIT (0x1<<0)
176 #define SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT 2
177 
178 #define SL_LIDAR_RESP_HQ_FLAG_SYNCBIT (0x1<<0)
179 
180 #define SL_LIDAR_RESP_MEASUREMENT_CHECKBIT (0x1<<0)
181 #define SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT 1
182 
184 {
187 } __attribute__((packed)) sl_lidar_response_sample_rate_t;
188 
190 {
191  sl_u8 sync_quality; // syncbit:1;syncbit_inverse:1;quality:6;
192  sl_u16 angle_q6_checkbit; // check_bit:1;angle_q6:15;
193  sl_u16 distance_q2;
194 } __attribute__((packed)) sl_lidar_response_measurement_node_t;
195 
196 //[distance_sync flags]
197 #define SL_LIDAR_RESP_MEASUREMENT_EXP_ANGLE_MASK (0x3)
198 #define SL_LIDAR_RESP_MEASUREMENT_EXP_DISTANCE_MASK (0xFC)
199 
201 {
202  sl_u16 distance_angle_1; // see [distance_sync flags]
203  sl_u16 distance_angle_2; // see [distance_sync flags]
205 } __attribute__((packed)) sl_lidar_response_cabin_nodes_t;
206 
207 
208 #define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNC_1 0xA
209 #define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNC_2 0x5
210 
211 #define SL_LIDAR_RESP_MEASUREMENT_HQ_SYNC 0xA5
212 
213 #define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNCBIT (0x1<<15)
214 
216 {
217  sl_u8 s_checksum_1; // see [s_checksum_1]
218  sl_u8 s_checksum_2; // see [s_checksum_1]
220  sl_lidar_response_cabin_nodes_t cabins[16];
221 } __attribute__((packed)) sl_lidar_response_capsule_measurement_nodes_t;
222 
224 {
225  sl_u16 distance;
226 } __attribute__((packed)) sl_lidar_response_dense_cabin_nodes_t;
227 
229 {
230  sl_u8 s_checksum_1; // see [s_checksum_1]
231  sl_u8 s_checksum_2; // see [s_checksum_1]
233  sl_lidar_response_dense_cabin_nodes_t cabins[40];
234 } __attribute__((packed)) sl_lidar_response_dense_capsule_measurement_nodes_t;
235 
236 
240 } __attribute__((packed)) sl_lidar_response_ultra_dense_cabin_nodes_t;
241 
243  sl_u8 s_checksum_1; // see [s_checksum_1]
244  sl_u8 s_checksum_2; // see [s_checksum_1]
245  sl_u32 time_stamp;
246  sl_u16 dev_status;
248  sl_lidar_response_ultra_dense_cabin_nodes_t cabins[32];
249 } __attribute__((packed)) sl_lidar_response_ultra_dense_capsule_measurement_nodes_t;
250 
251 
252 // ext1 : x2 boost mode
253 
254 #define SL_LIDAR_RESP_MEASUREMENT_EXP_ULTRA_MAJOR_BITS 12
255 #define SL_LIDAR_RESP_MEASUREMENT_EXP_ULTRA_PREDICT_BITS 10
256 
258 {
259  // 31 0
260  // | predict2 10bit | predict1 10bit | major 12bit |
261  sl_u32 combined_x3;
262 } __attribute__((packed)) sl_lidar_response_ultra_cabin_nodes_t;
263 
265 {
266  sl_u8 s_checksum_1; // see [s_checksum_1]
267  sl_u8 s_checksum_2; // see [s_checksum_1]
269  sl_lidar_response_ultra_cabin_nodes_t ultra_cabins[32];
270 } __attribute__((packed)) sl_lidar_response_ultra_capsule_measurement_nodes_t;
271 
273 {
274  sl_u16 angle_z_q14;
275  sl_u32 dist_mm_q2;
276  sl_u8 quality;
277  sl_u8 flag;
279 
281 {
282  sl_u8 sync_byte;
283  sl_u64 time_stamp;
285  sl_u32 crc32;
286 }__attribute__((packed)) sl_lidar_response_hq_capsule_measurement_nodes_t;
287 
288 
289 # define SL_LIDAR_CONF_SCAN_COMMAND_STD 0
290 # define SL_LIDAR_CONF_SCAN_COMMAND_EXPRESS 1
291 # define SL_LIDAR_CONF_SCAN_COMMAND_HQ 2
292 # define SL_LIDAR_CONF_SCAN_COMMAND_BOOST 3
293 # define SL_LIDAR_CONF_SCAN_COMMAND_STABILITY 4
294 # define SL_LIDAR_CONF_SCAN_COMMAND_SENSITIVITY 5
295 
296 #define SL_LIDAR_CONF_ANGLE_RANGE 0x00000000
297 #define SL_LIDAR_CONF_DESIRED_ROT_FREQ 0x00000001
298 #define SL_LIDAR_CONF_SCAN_COMMAND_BITMAP 0x00000002
299 #define SL_LIDAR_CONF_MIN_ROT_FREQ 0x00000004
300 #define SL_LIDAR_CONF_MAX_ROT_FREQ 0x00000005
301 #define SL_LIDAR_CONF_MAX_DISTANCE 0x00000060
302 
303 #define SL_LIDAR_CONF_SCAN_MODE_COUNT 0x00000070
304 #define SL_LIDAR_CONF_SCAN_MODE_US_PER_SAMPLE 0x00000071
305 #define SL_LIDAR_CONF_SCAN_MODE_MAX_DISTANCE 0x00000074
306 #define SL_LIDAR_CONF_SCAN_MODE_ANS_TYPE 0x00000075
307 #define SL_LIDAR_CONF_LIDAR_MAC_ADDR 0x00000079
308 #define SL_LIDAR_CONF_SCAN_MODE_TYPICAL 0x0000007C
309 #define SL_LIDAR_CONF_SCAN_MODE_NAME 0x0000007F
310 
311 
312 #define SL_LIDAR_CONF_MODEL_REVISION_ID 0x00000080
313 #define SL_LIDAR_CONF_MODEL_NAME_ALIAS 0x00000081
314 
315 #define SL_LIDAR_CONF_DETECTED_SERIAL_BPS 0x000000A1
316 
317 #define SL_LIDAR_CONF_LIDAR_STATIC_IP_ADDR 0x0001CCC0
318 #define SL_LIDAR_EXPRESS_SCAN_STABILITY_BITMAP 4
319 #define SL_LIDAR_EXPRESS_SCAN_SENSITIVITY_BITMAP 5
320 
322 {
323  sl_u32 type;
324  sl_u8 payload[0];
325 }__attribute__((packed)) sl_lidar_response_get_lidar_conf_t;
326 
328 {
329  sl_u32 type;
330  sl_u32 result;
331 }__attribute__((packed)) sl_lidar_response_set_lidar_conf_t;
332 
333 
335 {
336  sl_u8 model;
339  sl_u8 serialnum[16];
340 } __attribute__((packed)) sl_lidar_response_device_info_t;
341 
343 {
344  sl_u8 status;
345  sl_u16 error_code;
346 } __attribute__((packed)) sl_lidar_response_device_health_t;
347 
348 typedef struct _sl_lidar_ip_conf_t {
349  sl_u8 ip_addr[4];
350  sl_u8 net_mask[4];
351  sl_u8 gw[4];
352 }__attribute__((packed)) sl_lidar_ip_conf_t;
353 
355  sl_u8 macaddr[6];
356 } __attribute__((packed)) sl_lidar_response_device_macaddr_info_t;
357 
359  sl_u16 rpm;
360  sl_u16 pwm_ref;
361 }__attribute__((packed)) sl_lidar_response_desired_rot_speed_t;
362 
363 // Definition of the variable bit scale encoding mechanism
364 #define SL_LIDAR_VARBITSCALE_X2_SRC_BIT 9
365 #define SL_LIDAR_VARBITSCALE_X4_SRC_BIT 11
366 #define SL_LIDAR_VARBITSCALE_X8_SRC_BIT 12
367 #define SL_LIDAR_VARBITSCALE_X16_SRC_BIT 14
368 
369 #define SL_LIDAR_VARBITSCALE_X2_DEST_VAL 512
370 #define SL_LIDAR_VARBITSCALE_X4_DEST_VAL 1280
371 #define SL_LIDAR_VARBITSCALE_X8_DEST_VAL 1792
372 #define SL_LIDAR_VARBITSCALE_X16_DEST_VAL 3328
373 
374 #define SL_LIDAR_VARBITSCALE_GET_SRC_MAX_VAL_BY_BITS(_BITS_) \
375  ( (((0x1<<(_BITS_)) - SL_LIDAR_VARBITSCALE_X16_DEST_VAL)<<4) + \
376  ((SL_LIDAR_VARBITSCALE_X16_DEST_VAL - SL_LIDAR_VARBITSCALE_X8_DEST_VAL)<<3) + \
377  ((SL_LIDAR_VARBITSCALE_X8_DEST_VAL - SL_LIDAR_VARBITSCALE_X4_DEST_VAL)<<2) + \
378  ((SL_LIDAR_VARBITSCALE_X4_DEST_VAL - SL_LIDAR_VARBITSCALE_X2_DEST_VAL)<<1) + \
379  SL_LIDAR_VARBITSCALE_X2_DEST_VAL - 1)
380 
381 
382 #if defined(_WIN32)
383 #pragma pack()
384 #endif
385 
386 #if defined(_MSC_VER)
387 #pragma warning(pop)
388 #endif
_sl_lidar_response_get_lidar_conf::type
sl_u32 type
Definition: sl_lidar_cmd.h:323
_sl_lidar_response_device_health_t::status
sl_u8 status
Definition: sl_lidar_cmd.h:344
_sl_lidar_response_device_health_t::error_code
sl_u16 error_code
Definition: sl_lidar_cmd.h:345
_sl_lidar_response_acc_board_flag_t
Definition: sl_lidar_cmd.h:165
_sl_lidar_response_device_health_t
Definition: sl_lidar_cmd.h:342
_sl_lidar_response_device_info_t::serialnum
sl_u8 serialnum[16]
Definition: sl_lidar_cmd.h:339
_sl_lidar_payload_get_scan_conf_t::type
sl_u32 type
Definition: sl_lidar_cmd.h:108
_sl_lidar_response_capsule_measurement_nodes_t
Definition: sl_lidar_cmd.h:215
_sl_lidar_response_dense_cabin_nodes_t::distance
sl_u16 distance
Definition: sl_lidar_cmd.h:225
_sl_lidar_ip_conf_t::gw
sl_u8 gw[4]
Definition: sl_lidar_cmd.h:351
_sl_lidar_response_get_lidar_conf
Definition: sl_lidar_cmd.h:321
sl_lidar_response_measurement_node_hq_t
Definition: sl_lidar_cmd.h:272
_sl_lidar_response_set_lidar_conf::result
sl_u32 result
Definition: sl_lidar_cmd.h:330
__attribute__
struct _sl_lidar_payload_express_scan_t __attribute__((packed)) sl_lidar_payload_express_scan_t
_sl_lidar_response_device_info_t::hardware_version
sl_u8 hardware_version
Definition: sl_lidar_cmd.h:338
_sl_lidar_response_hq_capsule_measurement_nodes_t::crc32
sl_u32 crc32
Definition: sl_lidar_cmd.h:285
_sl_lidar_payload_motor_pwm_t::pwm_value
sl_u16 pwm_value
Definition: sl_lidar_cmd.h:120
_sl_lidar_response_device_info_t
Definition: sl_lidar_cmd.h:334
_sl_lidar_response_dense_capsule_measurement_nodes_t::s_checksum_2
sl_u8 s_checksum_2
Definition: sl_lidar_cmd.h:231
_sl_lidar_response_ultra_dense_cabin_nodes_t
Definition: sl_lidar_cmd.h:237
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t::s_checksum_1
sl_u8 s_checksum_1
Definition: sl_lidar_cmd.h:243
_sl_lidar_payload_new_bps_confirmation_t::required_bps
sl_u32 required_bps
Definition: sl_lidar_cmd.h:135
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t::s_checksum_2
sl_u8 s_checksum_2
Definition: sl_lidar_cmd.h:244
_sl_lidar_response_ultra_capsule_measurement_nodes_t::ultra_cabins
sl_lidar_response_ultra_cabin_nodes_t ultra_cabins[32]
Definition: sl_lidar_cmd.h:269
_sl_lidar_response_dense_capsule_measurement_nodes_t
Definition: sl_lidar_cmd.h:228
_sl_lidar_response_measurement_node_t::angle_q6_checkbit
sl_u16 angle_q6_checkbit
Definition: sl_lidar_cmd.h:192
_sl_lidar_response_ultra_capsule_measurement_nodes_t::s_checksum_2
sl_u8 s_checksum_2
Definition: sl_lidar_cmd.h:267
_sl_lidar_response_dense_cabin_nodes_t
Definition: sl_lidar_cmd.h:223
_sl_lidar_payload_express_scan_t::working_mode
sl_u8 working_mode
Definition: sl_lidar_cmd.h:95
_sl_lidar_response_set_lidar_conf::type
sl_u32 type
Definition: sl_lidar_cmd.h:329
_sl_lidar_response_desired_rot_speed_t::pwm_ref
sl_u16 pwm_ref
Definition: sl_lidar_cmd.h:360
_sl_lidar_ip_conf_t
Definition: sl_lidar_cmd.h:348
_sl_lidar_response_cabin_nodes_t::distance_angle_1
sl_u16 distance_angle_1
Definition: sl_lidar_cmd.h:202
_sl_lidar_response_device_macaddr_info_t::macaddr
sl_u8 macaddr[6]
Definition: sl_lidar_cmd.h:355
_sl_lidar_response_sample_rate_t::std_sample_duration_us
sl_u16 std_sample_duration_us
Definition: sl_lidar_cmd.h:185
sl_lidar_protocol.h
_sl_lidar_response_acc_board_flag_t::support_flag
sl_u32 support_flag
Definition: sl_lidar_cmd.h:167
_sl_lidar_payload_get_scan_conf_t
Definition: sl_lidar_cmd.h:106
_sl_lidar_payload_hq_scan_t::reserved
sl_u8 reserved[32]
Definition: sl_lidar_cmd.h:103
_sl_lidar_payload_motor_pwm_t
Definition: sl_lidar_cmd.h:118
_sl_lidar_response_device_info_t::model
sl_u8 model
Definition: sl_lidar_cmd.h:336
_sl_lidar_ip_conf_t::ip_addr
sl_u8 ip_addr[4]
Definition: sl_lidar_cmd.h:349
_sl_lidar_payload_express_scan_t::working_flags
sl_u16 working_flags
Definition: sl_lidar_cmd.h:96
_sl_lidar_payload_express_scan_t::param
sl_u16 param
Definition: sl_lidar_cmd.h:97
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t::cabins
sl_lidar_response_ultra_dense_cabin_nodes_t cabins[32]
Definition: sl_lidar_cmd.h:248
_sl_lidar_payload_hq_scan_t
Definition: sl_lidar_cmd.h:100
_sl_lidar_response_ultra_dense_cabin_nodes_t::qualityh_array
sl_u8 qualityh_array
Definition: sl_lidar_cmd.h:239
_sl_lidar_response_capsule_measurement_nodes_t::s_checksum_2
sl_u8 s_checksum_2
Definition: sl_lidar_cmd.h:218
_sl_payload_set_scan_conf_t
Definition: sl_lidar_cmd.h:111
_sl_lidar_response_capsule_measurement_nodes_t::s_checksum_1
sl_u8 s_checksum_1
Definition: sl_lidar_cmd.h:217
_sl_lidar_response_measurement_node_t::sync_quality
sl_u8 sync_quality
Definition: sl_lidar_cmd.h:191
_sl_lidar_response_ultra_capsule_measurement_nodes_t::s_checksum_1
sl_u8 s_checksum_1
Definition: sl_lidar_cmd.h:266
_sl_lidar_response_device_info_t::firmware_version
sl_u16 firmware_version
Definition: sl_lidar_cmd.h:337
_sl_lidar_response_cabin_nodes_t::offset_angles_q3
sl_u8 offset_angles_q3
Definition: sl_lidar_cmd.h:204
_sl_lidar_response_cabin_nodes_t::distance_angle_2
sl_u16 distance_angle_2
Definition: sl_lidar_cmd.h:203
sl_lidar_response_measurement_node_hq_t::quality
sl_u8 quality
Definition: sl_lidar_cmd.h:276
_sl_lidar_payload_hq_spd_ctrl_t::rpm
sl_u16 rpm
Definition: sl_lidar_cmd.h:129
_sl_lidar_response_capsule_measurement_nodes_t::start_angle_sync_q6
sl_u16 start_angle_sync_q6
Definition: sl_lidar_cmd.h:219
_sl_lidar_response_capsule_measurement_nodes_t::cabins
sl_lidar_response_cabin_nodes_t cabins[16]
Definition: sl_lidar_cmd.h:220
sl_lidar_response_measurement_node_hq_t::dist_mm_q2
sl_u32 dist_mm_q2
Definition: sl_lidar_cmd.h:275
_sl_lidar_response_cabin_nodes_t
Definition: sl_lidar_cmd.h:200
_sl_lidar_response_get_lidar_conf::payload
sl_u8 payload[0]
Definition: sl_lidar_cmd.h:324
_sl_lidar_response_desired_rot_speed_t::rpm
sl_u16 rpm
Definition: sl_lidar_cmd.h:359
_sl_lidar_response_hq_capsule_measurement_nodes_t::node_hq
sl_lidar_response_measurement_node_hq_t node_hq[96]
Definition: sl_lidar_cmd.h:284
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t::start_angle_sync_q6
sl_u16 start_angle_sync_q6
Definition: sl_lidar_cmd.h:247
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t::time_stamp
sl_u32 time_stamp
Definition: sl_lidar_cmd.h:245
sl_lidar_response_measurement_node_hq_t::angle_z_q14
sl_u16 angle_z_q14
Definition: sl_lidar_cmd.h:274
_sl_lidar_response_measurement_node_t::distance_q2
sl_u16 distance_q2
Definition: sl_lidar_cmd.h:193
_sl_lidar_response_hq_capsule_measurement_nodes_t::time_stamp
sl_u64 time_stamp
Definition: sl_lidar_cmd.h:283
_sl_lidar_response_dense_capsule_measurement_nodes_t::s_checksum_1
sl_u8 s_checksum_1
Definition: sl_lidar_cmd.h:230
_sl_lidar_response_ultra_capsule_measurement_nodes_t::start_angle_sync_q6
sl_u16 start_angle_sync_q6
Definition: sl_lidar_cmd.h:268
_sl_lidar_payload_acc_board_flag_t::reserved
sl_u32 reserved
Definition: sl_lidar_cmd.h:125
_sl_lidar_response_ultra_capsule_measurement_nodes_t
Definition: sl_lidar_cmd.h:264
_sl_lidar_payload_new_bps_confirmation_t::param
sl_u16 param
Definition: sl_lidar_cmd.h:136
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t::dev_status
sl_u16 dev_status
Definition: sl_lidar_cmd.h:246
_sl_lidar_response_ultra_cabin_nodes_t
Definition: sl_lidar_cmd.h:257
_sl_lidar_payload_express_scan_t
Definition: sl_lidar_cmd.h:93
_sl_payload_set_scan_conf_t::type
sl_u32 type
Definition: sl_lidar_cmd.h:112
_sl_lidar_payload_hq_scan_t::flag
sl_u8 flag
Definition: sl_lidar_cmd.h:102
_sl_lidar_response_dense_capsule_measurement_nodes_t::cabins
sl_lidar_response_dense_cabin_nodes_t cabins[40]
Definition: sl_lidar_cmd.h:233
_sl_lidar_response_ultra_dense_cabin_nodes_t::qualityl_distance_scale
sl_u16 qualityl_distance_scale[2]
Definition: sl_lidar_cmd.h:238
_sl_lidar_response_measurement_node_t
Definition: sl_lidar_cmd.h:189
_sl_lidar_response_ultra_dense_capsule_measurement_nodes_t
Definition: sl_lidar_cmd.h:242
_sl_lidar_payload_acc_board_flag_t
Definition: sl_lidar_cmd.h:123
_sl_lidar_ip_conf_t::net_mask
sl_u8 net_mask[4]
Definition: sl_lidar_cmd.h:350
_sl_lidar_payload_new_bps_confirmation_t::flag
sl_u16 flag
Definition: sl_lidar_cmd.h:134
_sl_lidar_response_dense_capsule_measurement_nodes_t::start_angle_sync_q6
sl_u16 start_angle_sync_q6
Definition: sl_lidar_cmd.h:232
_sl_lidar_response_desired_rot_speed_t
Definition: sl_lidar_cmd.h:358
sl_lidar_response_measurement_node_hq_t::flag
sl_u8 flag
Definition: sl_lidar_cmd.h:277
_sl_lidar_response_sample_rate_t::express_sample_duration_us
sl_u16 express_sample_duration_us
Definition: sl_lidar_cmd.h:186
_sl_lidar_response_hq_capsule_measurement_nodes_t
Definition: sl_lidar_cmd.h:280
_sl_lidar_response_hq_capsule_measurement_nodes_t::sync_byte
sl_u8 sync_byte
Definition: sl_lidar_cmd.h:282
_sl_lidar_payload_hq_spd_ctrl_t
Definition: sl_lidar_cmd.h:128
_sl_lidar_response_set_lidar_conf
Definition: sl_lidar_cmd.h:327
_sl_lidar_payload_new_bps_confirmation_t
Definition: sl_lidar_cmd.h:133
_sl_lidar_response_ultra_cabin_nodes_t::combined_x3
sl_u32 combined_x3
Definition: sl_lidar_cmd.h:261
_sl_lidar_response_device_macaddr_info_t
Definition: sl_lidar_cmd.h:354
_sl_lidar_response_sample_rate_t
Definition: sl_lidar_cmd.h:183


rplidar_ros
Author(s):
autogenerated on Fri Aug 2 2024 08:42:14