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 #include "sl_lidar_protocol.h"
37 
38  // Commands
39  //-----------------------------------------
40 
41 
42 #define SL_LIDAR_AUTOBAUD_MAGICBYTE 0x41
43 
44  // Commands without payload and response
45 #define SL_LIDAR_CMD_STOP 0x25
46 #define SL_LIDAR_CMD_SCAN 0x20
47 #define SL_LIDAR_CMD_FORCE_SCAN 0x21
48 #define SL_LIDAR_CMD_RESET 0x40
49 
50 // Commands with payload but no response
51 #define SL_LIDAR_CMD_NEW_BAUDRATE_CONFIRM 0x90 //added in fw 1.30
52 
53 // Commands without payload but have response
54 #define SL_LIDAR_CMD_GET_DEVICE_INFO 0x50
55 #define SL_LIDAR_CMD_GET_DEVICE_HEALTH 0x52
56 
57 #define SL_LIDAR_CMD_GET_SAMPLERATE 0x59 //added in fw 1.17
58 
59 #define SL_LIDAR_CMD_HQ_MOTOR_SPEED_CTRL 0xA8
60 
61 
62 // Commands with payload and have response
63 #define SL_LIDAR_CMD_EXPRESS_SCAN 0x82 //added in fw 1.17
64 #define SL_LIDAR_CMD_HQ_SCAN 0x83 //added in fw 1.24
65 #define SL_LIDAR_CMD_GET_LIDAR_CONF 0x84 //added in fw 1.24
66 #define SL_LIDAR_CMD_SET_LIDAR_CONF 0x85 //added in fw 1.24
67 //add for A2 to set RPLIDAR motor pwm when using accessory board
68 #define SL_LIDAR_CMD_SET_MOTOR_PWM 0xF0
69 #define SL_LIDAR_CMD_GET_ACC_BOARD_FLAG 0xFF
70 
71 #if defined(_WIN32)
72 #pragma pack(1)
73 #endif
74 
75 
76 // Payloads
77 // ------------------------------------------
78 #define SL_LIDAR_EXPRESS_SCAN_MODE_NORMAL 0
79 #define SL_LIDAR_EXPRESS_SCAN_MODE_FIXANGLE 0 // won't been supported but keep to prevent build fail
80 //for express working flag(extending express scan protocol)
81 #define SL_LIDAR_EXPRESS_SCAN_FLAG_BOOST 0x0001
82 #define SL_LIDAR_EXPRESS_SCAN_FLAG_SUNLIGHT_REJECTION 0x0002
83 
84 //for ultra express working flag
85 #define SL_LIDAR_ULTRAEXPRESS_SCAN_FLAG_STD 0x0001
86 #define SL_LIDAR_ULTRAEXPRESS_SCAN_FLAG_HIGH_SENSITIVITY 0x0002
87 
89 {
90  sl_u8 working_mode;
91  sl_u16 working_flags;
92  sl_u16 param;
93 } __attribute__((packed)) sl_lidar_payload_express_scan_t;
94 
96 {
97  sl_u8 flag;
98  sl_u8 reserved[32];
99 } __attribute__((packed)) sl_lidar_payload_hq_scan_t;
100 
102 {
103  sl_u32 type;
104  sl_u8 reserved[32];
105 } __attribute__((packed)) sl_lidar_payload_get_scan_conf_t;
106 
108  sl_u32 type;
109 } __attribute__((packed)) sl_lidar_payload_set_scan_conf_t;
110 
111 
112 #define DEFAULT_MOTOR_SPEED (0xFFFFu)
113 
115 {
116  sl_u16 pwm_value;
117 } __attribute__((packed)) sl_lidar_payload_motor_pwm_t;
118 
120 {
121  sl_u32 reserved;
122 } __attribute__((packed)) sl_lidar_payload_acc_board_flag_t;
123 
125  sl_u16 rpm;
126 } __attribute__((packed))sl_lidar_payload_hq_spd_ctrl_t;
127 
128 
130  sl_u16 flag; // reserved, must be 0x5F5F
131  sl_u32 required_bps;
132  sl_u16 param;
133 } __attribute__((packed)) sl_lidar_payload_new_bps_confirmation_t;
134 
135 // Response
136 // ------------------------------------------
137 #define SL_LIDAR_ANS_TYPE_DEVINFO 0x4
138 #define SL_LIDAR_ANS_TYPE_DEVHEALTH 0x6
139 
140 #define SL_LIDAR_ANS_TYPE_MEASUREMENT 0x81
141 // Added in FW ver 1.17
142 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_CAPSULED 0x82
143 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_HQ 0x83
144 
145 
146 // Added in FW ver 1.17
147 #define SL_LIDAR_ANS_TYPE_SAMPLE_RATE 0x15
148 //added in FW ver 1.23alpha
149 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_CAPSULED_ULTRA 0x84
150 //added in FW ver 1.24
151 #define SL_LIDAR_ANS_TYPE_GET_LIDAR_CONF 0x20
152 #define SL_LIDAR_ANS_TYPE_SET_LIDAR_CONF 0x21
153 #define SL_LIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED 0x85
154 #define SL_LIDAR_ANS_TYPE_ACC_BOARD_FLAG 0xFF
155 
156 #define SL_LIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK (0x1)
158 {
159  sl_u32 support_flag;
160 } __attribute__((packed)) sl_lidar_response_acc_board_flag_t;
161 
162 
163 #define SL_LIDAR_STATUS_OK 0x0
164 #define SL_LIDAR_STATUS_WARNING 0x1
165 #define SL_LIDAR_STATUS_ERROR 0x2
166 
167 #define SL_LIDAR_RESP_MEASUREMENT_SYNCBIT (0x1<<0)
168 #define SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT 2
169 
170 #define SL_LIDAR_RESP_HQ_FLAG_SYNCBIT (0x1<<0)
171 
172 #define SL_LIDAR_RESP_MEASUREMENT_CHECKBIT (0x1<<0)
173 #define SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT 1
174 
176 {
179 } __attribute__((packed)) sl_lidar_response_sample_rate_t;
180 
182 {
183  sl_u8 sync_quality; // syncbit:1;syncbit_inverse:1;quality:6;
184  sl_u16 angle_q6_checkbit; // check_bit:1;angle_q6:15;
185  sl_u16 distance_q2;
186 } __attribute__((packed)) sl_lidar_response_measurement_node_t;
187 
188 //[distance_sync flags]
189 #define SL_LIDAR_RESP_MEASUREMENT_EXP_ANGLE_MASK (0x3)
190 #define SL_LIDAR_RESP_MEASUREMENT_EXP_DISTANCE_MASK (0xFC)
191 
193 {
194  sl_u16 distance_angle_1; // see [distance_sync flags]
195  sl_u16 distance_angle_2; // see [distance_sync flags]
197 } __attribute__((packed)) sl_lidar_response_cabin_nodes_t;
198 
199 
200 #define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNC_1 0xA
201 #define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNC_2 0x5
202 
203 #define SL_LIDAR_RESP_MEASUREMENT_HQ_SYNC 0xA5
204 
205 #define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNCBIT (0x1<<15)
206 
208 {
209  sl_u8 s_checksum_1; // see [s_checksum_1]
210  sl_u8 s_checksum_2; // see [s_checksum_1]
212  sl_lidar_response_cabin_nodes_t cabins[16];
213 } __attribute__((packed)) sl_lidar_response_capsule_measurement_nodes_t;
214 
216 {
217  sl_u16 distance;
218 } __attribute__((packed)) sl_lidar_response_dense_cabin_nodes_t;
219 
221 {
222  sl_u8 s_checksum_1; // see [s_checksum_1]
223  sl_u8 s_checksum_2; // see [s_checksum_1]
225  sl_lidar_response_dense_cabin_nodes_t cabins[40];
226 } __attribute__((packed)) sl_lidar_response_dense_capsule_measurement_nodes_t;
227 
228 // ext1 : x2 boost mode
229 
230 #define SL_LIDAR_RESP_MEASUREMENT_EXP_ULTRA_MAJOR_BITS 12
231 #define SL_LIDAR_RESP_MEASUREMENT_EXP_ULTRA_PREDICT_BITS 10
232 
234 {
235  // 31 0
236  // | predict2 10bit | predict1 10bit | major 12bit |
237  sl_u32 combined_x3;
238 } __attribute__((packed)) sl_lidar_response_ultra_cabin_nodes_t;
239 
241 {
242  sl_u8 s_checksum_1; // see [s_checksum_1]
243  sl_u8 s_checksum_2; // see [s_checksum_1]
245  sl_lidar_response_ultra_cabin_nodes_t ultra_cabins[32];
246 } __attribute__((packed)) sl_lidar_response_ultra_capsule_measurement_nodes_t;
247 
249 {
250  sl_u16 angle_z_q14;
251  sl_u32 dist_mm_q2;
252  sl_u8 quality;
253  sl_u8 flag;
255 
257 {
258  sl_u8 sync_byte;
259  sl_u64 time_stamp;
261  sl_u32 crc32;
262 }__attribute__((packed)) sl_lidar_response_hq_capsule_measurement_nodes_t;
263 
264 
265 # define SL_LIDAR_CONF_SCAN_COMMAND_STD 0
266 # define SL_LIDAR_CONF_SCAN_COMMAND_EXPRESS 1
267 # define SL_LIDAR_CONF_SCAN_COMMAND_HQ 2
268 # define SL_LIDAR_CONF_SCAN_COMMAND_BOOST 3
269 # define SL_LIDAR_CONF_SCAN_COMMAND_STABILITY 4
270 # define SL_LIDAR_CONF_SCAN_COMMAND_SENSITIVITY 5
271 
272 #define SL_LIDAR_CONF_ANGLE_RANGE 0x00000000
273 #define SL_LIDAR_CONF_DESIRED_ROT_FREQ 0x00000001
274 #define SL_LIDAR_CONF_SCAN_COMMAND_BITMAP 0x00000002
275 #define SL_LIDAR_CONF_MIN_ROT_FREQ 0x00000004
276 #define SL_LIDAR_CONF_MAX_ROT_FREQ 0x00000005
277 #define SL_LIDAR_CONF_MAX_DISTANCE 0x00000060
278 
279 #define SL_LIDAR_CONF_SCAN_MODE_COUNT 0x00000070
280 #define SL_LIDAR_CONF_SCAN_MODE_US_PER_SAMPLE 0x00000071
281 #define SL_LIDAR_CONF_SCAN_MODE_MAX_DISTANCE 0x00000074
282 #define SL_LIDAR_CONF_SCAN_MODE_ANS_TYPE 0x00000075
283 #define SL_LIDAR_CONF_LIDAR_MAC_ADDR 0x00000079
284 #define SL_LIDAR_CONF_SCAN_MODE_TYPICAL 0x0000007C
285 #define SL_LIDAR_CONF_SCAN_MODE_NAME 0x0000007F
286 #define SL_LIDAR_CONF_DETECTED_SERIAL_BPS 0x000000A1
287 
288 #define SL_LIDAR_CONF_LIDAR_STATIC_IP_ADDR 0x0001CCC0
289 #define SL_LIDAR_EXPRESS_SCAN_STABILITY_BITMAP 4
290 #define SL_LIDAR_EXPRESS_SCAN_SENSITIVITY_BITMAP 5
291 
293 {
294  sl_u32 type;
295  sl_u8 payload[0];
296 }__attribute__((packed)) sl_lidar_response_get_lidar_conf_t;
297 
299 {
300  sl_u32 result;
301 }__attribute__((packed)) sl_lidar_response_set_lidar_conf_t;
302 
303 
305 {
306  sl_u8 model;
309  sl_u8 serialnum[16];
310 } __attribute__((packed)) sl_lidar_response_device_info_t;
311 
313 {
314  sl_u8 status;
315  sl_u16 error_code;
316 } __attribute__((packed)) sl_lidar_response_device_health_t;
317 
318 typedef struct _sl_lidar_ip_conf_t {
319  sl_u8 ip_addr[4];
320  sl_u8 net_mask[4];
321  sl_u8 gw[4];
322 }__attribute__((packed)) sl_lidar_ip_conf_t;
323 
325  sl_u8 macaddr[6];
326 } __attribute__((packed)) sl_lidar_response_device_macaddr_info_t;
327 
329  sl_u16 rpm;
330  sl_u16 pwm_ref;
331 }__attribute__((packed)) sl_lidar_response_desired_rot_speed_t;
332 
333 // Definition of the variable bit scale encoding mechanism
334 #define SL_LIDAR_VARBITSCALE_X2_SRC_BIT 9
335 #define SL_LIDAR_VARBITSCALE_X4_SRC_BIT 11
336 #define SL_LIDAR_VARBITSCALE_X8_SRC_BIT 12
337 #define SL_LIDAR_VARBITSCALE_X16_SRC_BIT 14
338 
339 #define SL_LIDAR_VARBITSCALE_X2_DEST_VAL 512
340 #define SL_LIDAR_VARBITSCALE_X4_DEST_VAL 1280
341 #define SL_LIDAR_VARBITSCALE_X8_DEST_VAL 1792
342 #define SL_LIDAR_VARBITSCALE_X16_DEST_VAL 3328
343 
344 #define SL_LIDAR_VARBITSCALE_GET_SRC_MAX_VAL_BY_BITS(_BITS_) \
345  ( (((0x1<<(_BITS_)) - SL_LIDAR_VARBITSCALE_X16_DEST_VAL)<<4) + \
346  ((SL_LIDAR_VARBITSCALE_X16_DEST_VAL - SL_LIDAR_VARBITSCALE_X8_DEST_VAL)<<3) + \
347  ((SL_LIDAR_VARBITSCALE_X8_DEST_VAL - SL_LIDAR_VARBITSCALE_X4_DEST_VAL)<<2) + \
348  ((SL_LIDAR_VARBITSCALE_X4_DEST_VAL - SL_LIDAR_VARBITSCALE_X2_DEST_VAL)<<1) + \
349  SL_LIDAR_VARBITSCALE_X2_DEST_VAL - 1)
350 
351 
352 #if defined(_WIN32)
353 #pragma pack()
354 #endif
sl_u8 reserved[32]
Definition: sl_lidar_cmd.h:44
sl_u8 macaddr[6]
Definition: sl_lidar_cmd.h:43
sl_u8 net_mask[4]
Definition: sl_lidar_cmd.h:44
struct _sl_lidar_payload_express_scan_t __attribute__((packed)) sl_lidar_payload_express_scan_t
sl_u8 gw[4]
Definition: sl_lidar_cmd.h:45
sl_u8 ip_addr[4]
Definition: sl_lidar_cmd.h:43
sl_lidar_response_measurement_node_hq_t node_hq[96]
Definition: sl_lidar_cmd.h:45
sl_u8 payload[0]
Definition: sl_lidar_cmd.h:44
sl_u8 serialnum[16]
Definition: sl_lidar_cmd.h:46
sl_lidar_response_cabin_nodes_t cabins[16]
Definition: sl_lidar_cmd.h:46
sl_lidar_response_ultra_cabin_nodes_t ultra_cabins[32]
Definition: sl_lidar_cmd.h:46


rplidar_ros
Author(s):
autogenerated on Tue Jun 13 2023 02:07:38