Apollo 10.0
自动驾驶开放平台
lslidar32_parser.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
18
19namespace apollo {
20namespace drivers {
21namespace lslidar {
22namespace parser {
23
25 LslidarParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
26 adjust_angle = 0;
27 adjust_angle_two = 0;
28 adjust_angle_three = 0;
29 adjust_angle_four = 0;
30 read_difop_ = true;
31 config_vert_angle = false;
32 lslidar_type = 2;
33}
34
36 const std::shared_ptr<LslidarScan>& scan_msg,
37 const std::shared_ptr<PointCloud>& out_msg) {
38 // allocate a point cloud with same time and frame ID as raw data
39 out_msg->mutable_header()->set_timestamp_sec(
40 scan_msg->basetime() / 1000000000.0);
41 out_msg->mutable_header()->set_module_name(
42 scan_msg->header().module_name());
43 out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id());
44 out_msg->set_height(1);
45 out_msg->set_measurement_time(scan_msg->basetime() / 1000000000.0);
46 out_msg->mutable_header()->set_sequence_num(
47 scan_msg->header().sequence_num());
48 gps_base_usec_ = scan_msg->basetime();
49
50 double scan_altitude_original_degree33[32];
51 double scan_altitude_original_degree1[32];
52 int startpos = 0;
53
54 const unsigned char* difop_ptr
55 = (const unsigned char*)scan_msg->difop_pkts(0).data().c_str();
56 if (difop_ptr[0] == 0xa5 && difop_ptr[1] == 0xff && difop_ptr[2] == 0x00
57 && difop_ptr[3] == 0x5a) {
58 if ((difop_ptr[1202] >= 0x02 && difop_ptr[1203] >= 0x80)
59 || difop_ptr[1202] == 0x03) {
60 lslidar_type = 3;
61 startpos = 245;
62 // Horizontal correction Angle
63 adjust_angle
64 = (difop_ptr[186] * 256
65 + difop_ptr[187]); // Angle correction A1
66 if (adjust_angle > 32767) {
67 adjust_angle = adjust_angle - 65535;
68 }
69 adjust_angle_two
70 = (difop_ptr[190] * 256
71 + difop_ptr[191]); // Angle correction A2
72 if (adjust_angle_two > 32767) {
73 adjust_angle_two = adjust_angle_two - 65535;
74 }
75 adjust_angle_three
76 = (difop_ptr[188] * 256
77 + difop_ptr[189]); // Angle correction A3
78 if (adjust_angle_three > 32767) {
79 adjust_angle_three = adjust_angle_three - 65535;
80 }
81 adjust_angle_four
82 = (difop_ptr[192] * 256
83 + difop_ptr[193]); // Angle correction A4
84 if (adjust_angle_four > 32767) {
85 adjust_angle_four = adjust_angle_four - 65535;
86 }
87 memcpy(scan_altitude_original_degree1,
88 scan_altitude_original_A3,
89 32 * 8);
90 memcpy(scan_altitude_original_degree33,
91 scan_altitude_original_C3,
92 32 * 8);
93
94 if (difop_ptr[185] == 0 || difop_ptr[185] == 1) {
95 int return_mode = difop_ptr[185] + 1;
96 config_.set_return_mode(return_mode);
97
98 if (difop_ptr[1195] == 0x21)
99 config_.set_degree_mode(2);
100 else
101 config_.set_degree_mode(1);
102
103 config_.set_distance_unit(0.4f);
104
105 for (int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
106 // 均匀1度校准两列
107 if (1 == config_.degree_mode()) {
108 cos_scan_altitude_caliration[i] = std::cos(
109 static_cast<float>(
110 scan_altitude_original_A3[i] * M_PI)
111 / 180.0f);
112 sin_scan_altitude_caliration[i] = std::sin(
113 static_cast<float>(
114 scan_altitude_original_A3[i] * M_PI)
115 / 180.0f);
116 scan_altitude_A[i] = scan_altitude_original_A3[i];
117 }
118 // 0.33度校准四列
119 if (2 == config_.degree_mode()) {
120 cos_scan_altitude_caliration[i] = std::cos(
121 static_cast<float>(
122 scan_altitude_original_C3[i] * M_PI)
123 / 180.0f);
124 sin_scan_altitude_caliration[i] = std::sin(
125 static_cast<float>(
126 scan_altitude_original_C3[i] * M_PI)
127 / 180.0f);
128 scan_altitude_C[i] = scan_altitude_original_C3[i];
129 }
130 }
131 }
132 } else {
133 lslidar_type = 2;
134 startpos = 882;
135 // Horizontal correction Angle
136 adjust_angle
137 = (difop_ptr[34] * 256
138 + difop_ptr[35]); /*Angle correction A1*/
139 if (adjust_angle > 32767) {
140 adjust_angle = adjust_angle - 65535;
141 }
142 adjust_angle_two
143 = (difop_ptr[42] * 256
144 + difop_ptr[43]); /*Angle correction A2*/
145 if (adjust_angle_two > 32767) {
146 adjust_angle_two = adjust_angle_two - 65535;
147 }
148 adjust_angle_three
149 = (difop_ptr[66] * 256
150 + difop_ptr[67]); /*Angle correction A3*/
151 if (adjust_angle_three > 32767) {
152 adjust_angle_three = adjust_angle_three - 65535;
153 }
154 adjust_angle_four
155 = (difop_ptr[68] * 256
156 + difop_ptr[69]); /*Angle correction A4*/
157 if (adjust_angle_four > 32767) {
158 adjust_angle_four = adjust_angle_four - 65535;
159 }
160 AWARN << "Load config failed, config file";
161 // Vertical Angle Calibration for device package
162 for (int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
163 // 均匀1度校准两列
164 if (1 == config_.degree_mode()) {
165 cos_scan_altitude_caliration[i] = std::cos(
166 static_cast<float>(
167 scan_altitude_original_A[i] * M_PI)
168 / 180.0f);
169 sin_scan_altitude_caliration[i] = std::sin(
170 static_cast<float>(
171 scan_altitude_original_A[i] * M_PI)
172 / 180.0f);
173 scan_altitude_A[i] = scan_altitude_original_A[i];
174 }
175 // 0.33度校准四列
176 if (2 == config_.degree_mode()) {
177 cos_scan_altitude_caliration[i] = std::cos(
178 static_cast<float>(
179 scan_altitude_original_C[i] * M_PI)
180 / 180.0f);
181 sin_scan_altitude_caliration[i] = std::sin(
182 static_cast<float>(
183 scan_altitude_original_C[i] * M_PI)
184 / 180.0f);
185 scan_altitude_C[i] = scan_altitude_original_C[i];
186 }
187 }
188 memcpy(scan_altitude_original_degree1,
189 scan_altitude_original_A,
190 32 * 8);
191 memcpy(scan_altitude_original_degree33,
192 scan_altitude_original_C,
193 32 * 8);
194 }
195 }
196
197 // Vertical Angle parse
198 if (config_.config_vert()) {
199 for (int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
200 uint8_t data1 = difop_ptr[startpos + 2 * i];
201 uint8_t data2 = difop_ptr[startpos + 2 * i + 1];
202 int vert_angle = data1 * 256 + data2;
203 if (vert_angle > 32767) {
204 vert_angle = vert_angle - 65535;
205 }
206 // 均匀1度校准两列
207 if (1 == config_.degree_mode()) {
208 scan_altitude_A[i]
209 = static_cast<double>(vert_angle * ROTATION_RESOLUTION);
210 if (fabs(scan_altitude_original_degree1[i] - scan_altitude_A[i])
211 > 1.5) {
212 scan_altitude_A[i] = scan_altitude_original_degree1[i];
213 }
214 config_vert_angle = true;
215 }
216 // 0.33度校准四列
217 if (2 == config_.degree_mode()) {
218 scan_altitude_C[i]
219 = static_cast<double>(vert_angle * ROTATION_RESOLUTION);
220 if (fabs(scan_altitude_original_degree33[i]
221 - scan_altitude_C[i])
222 > 1.5) {
223 scan_altitude_C[i] = scan_altitude_original_degree33[i];
224 }
225 config_vert_angle = true;
226 }
227 }
228 }
229
230 size_t packets_size = scan_msg->firing_pkts_size();
231 block_num = 0;
232 packet_number_ = packets_size;
233
234 AINFO << "packets_size :" << packets_size;
235
236 for (size_t i = 0; i < packets_size; ++i) {
237 Unpack(scan_msg->firing_pkts(static_cast<int>(i)), out_msg, i);
238 last_time_stamp_ = out_msg->measurement_time();
239 ADEBUG << "stamp: " << std::fixed << last_time_stamp_;
240 }
241
242 if (out_msg->point().empty()) {
243 // we discard this pointcloud if empty
244 AERROR << "All points is NAN!Please check lslidar:" << config_.model();
245 }
246
247 // set default width
248 out_msg->set_width(out_msg->point_size());
249}
250
255void Lslidar32Parser::Unpack(
256 const LslidarPacket& pkt,
257 std::shared_ptr<PointCloud> pc,
258 int packet_number) {
259 float x, y, z;
260 float azimuth = 0.0f;
261 uint32_t intensity = 0;
262 float azimuth_diff = 0.0f;
263 float azimuth_corrected_f = 0.0f;
264 float azimuth_corrected_offset_f = 0.0f;
265 uint64_t point_time;
266 uint64_t packet_end_time;
267
268 if (config_vert_angle) {
269 for (int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
270 // 均匀1度校准两列
271 if (1 == config_.degree_mode()) {
272 cos_scan_altitude_caliration[i] = std::cos(
273 static_cast<float>(scan_altitude_A[i] * M_PI) / 180.0f);
274 sin_scan_altitude_caliration[i] = std::sin(
275 static_cast<float>(scan_altitude_A[i] * M_PI) / 180.0f);
276 }
277
278 // 0.33度校准四列
279 if (2 == config_.degree_mode()) {
280 cos_scan_altitude_caliration[i] = std::cos(
281 static_cast<float>(scan_altitude_C[i] * M_PI) / 180.0f);
282 sin_scan_altitude_caliration[i] = std::sin(
283 static_cast<float>(scan_altitude_C[i] * M_PI) / 180.0f);
284 }
285 }
286 config_vert_angle = false;
287 }
288
289 const raw_packet_t* raw = (const raw_packet_t*)pkt.data().c_str();
291 packet_end_time = pkt.stamp();
292 } else {
293 packet_end_time = pkt.stamp();
294 }
295 current_packet_time = packet_end_time;
296
297 int point_count = -1;
298 for (int block = 0; block < BLOCKS_PER_PACKET; block++, block_num++) {
299 if (UPPER_BANK != raw->blocks[block].header)
300 break;
301
302 azimuth = static_cast<float>(
303 256 * raw->blocks[block].rotation_2
304 + raw->blocks[block].rotation_1);
305
306 if (2 == config_.return_mode()) {
307 if (block < (BLOCKS_PER_PACKET - 2)) {
308 int azi1, azi2;
309 azi1 = 256 * raw->blocks[block + 2].rotation_2
310 + raw->blocks[block + 2].rotation_1;
311 azi2 = 256 * raw->blocks[block].rotation_2
312 + raw->blocks[block].rotation_1;
313 azimuth_diff
314 = static_cast<float>((36000 + azi1 - azi2) % 36000);
315 } else {
316 int azi1, azi2;
317 azi1 = 256 * raw->blocks[block].rotation_2
318 + raw->blocks[block].rotation_1;
319 azi2 = 256 * raw->blocks[block - 2].rotation_2
320 + raw->blocks[block - 2].rotation_1;
321 azimuth_diff
322 = static_cast<float>((36000 + azi1 - azi2) % 36000);
323 }
324 azimuth_diff
325 = azimuth_diff < 0 ? azimuth_diff + 36000 : azimuth_diff;
326 azimuth_diff = azimuth_diff > 36000 ? azimuth_diff - 36000
327 : azimuth_diff;
328 } else {
329 if (block < (BLOCKS_PER_PACKET - 1)) {
330 int azi1, azi2;
331 azi1 = 256 * raw->blocks[block + 1].rotation_2
332 + raw->blocks[block + 1].rotation_1;
333 azi2 = 256 * raw->blocks[block].rotation_2
334 + raw->blocks[block].rotation_1;
335 azimuth_diff
336 = static_cast<float>((36000 + azi1 - azi2) % 36000);
337 } else {
338 int azi1, azi2;
339 azi1 = 256 * raw->blocks[block].rotation_2
340 + raw->blocks[block].rotation_1;
341 azi2 = 256 * raw->blocks[block - 1].rotation_2
342 + raw->blocks[block - 1].rotation_1;
343 azimuth_diff
344 = static_cast<float>((36000 + azi1 - azi2) % 36000);
345 }
346 azimuth_diff
347 = azimuth_diff < 0 ? azimuth_diff + 36000 : azimuth_diff;
348 azimuth_diff = azimuth_diff > 36000 ? azimuth_diff - 36000
349 : azimuth_diff;
350 }
351
352 for (int firing = 0, k = 0; firing < LSC32_FIRINGS_PER_BLOCK;
353 ++firing) {
354 for (int dsr = 0; dsr < LSC32_SCANS_PER_FIRING;
355 ++dsr, k += RAW_SCAN_SIZE) {
356 point_count++;
359 LaserCorrection& corrections
361
362 azimuth_corrected_f
363 = azimuth + azimuth_diff / LSC32_SCANS_PER_FIRING * dsr;
364 azimuth_corrected_f = azimuth_corrected_f < 0
365 ? azimuth_corrected_f + 36000
366 : azimuth_corrected_f;
367 azimuth_corrected_f = azimuth_corrected_f > 36000
368 ? azimuth_corrected_f - 36000
369 : azimuth_corrected_f;
370
371 // distance
372 union two_bytes tmp;
373 tmp.bytes[0] = raw->blocks[block].data[k];
374 tmp.bytes[1] = raw->blocks[block].data[k + 1];
375 int distance = tmp.uint;
376
377 // read intensity
378 intensity = raw->blocks[block].data[k + 2];
379
380 float distance2 = (distance * DISTANCE_RESOLUTION)
382
383 if (config_.calibration())
384 distance2 = distance2 + corrections.dist_correction;
385
386 if (2 == config_.return_mode()) {
387 if (previous_packet_time > 1e-6) {
388 point_time = current_packet_time
389 - (SCANS_PER_PACKET - point_count - 1)
392 / (SCANS_PER_PACKET);
393 } else { // fist packet
394 point_time = current_packet_time;
395 }
396
397 } else {
398 if (previous_packet_time > 1e-6) {
399 point_time = current_packet_time
400 - (SCANS_PER_PACKET - point_count - 1)
403 / (SCANS_PER_PACKET);
404 } else { // fist packet
405 point_time = current_packet_time;
406 }
407 }
408
409 if (distance2 > config_.max_range()
410 || distance2 < config_.min_range()) {
411 PointXYZIT* point = pc->add_point();
412 point->set_x(nan);
413 point->set_y(nan);
414 point->set_z(nan);
415 point->set_timestamp(point_time);
416 point->set_intensity(0);
417 } else {
418 // 均匀1度校准两列
419 if (1 == config_.degree_mode()) {
420 double adjust_diff = adjust_angle_two - adjust_angle;
421 if (adjust_diff > 300 && adjust_diff < 460) {
422 // v2.7 calibrtation
423 if (lslidar_type == 3) {
424 if (1 >= dsr % 4) {
425 azimuth_corrected_f += adjust_angle_two;
426 } else {
427 azimuth_corrected_f += adjust_angle;
428 }
429 } else {
430 if (0 == dsr % 2) {
431 azimuth_corrected_f += adjust_angle_two;
432 } else {
433 azimuth_corrected_f += adjust_angle;
434 }
435 }
436 } else {
437 // v2.6 calibrtation
438 if (0 == dsr % 2) {
439 azimuth_corrected_f += adjust_angle;
440 } else {
441 azimuth_corrected_f -= adjust_angle;
442 }
443 }
444 }
445
446 // 0.33度校准四列
447 if (2 == config_.degree_mode()) {
448 double adjust_diff_one
449 = adjust_angle_two - adjust_angle;
450 double adjust_diff_two
451 = adjust_angle_four - adjust_angle_three;
452 if (lslidar_type == 3) {
453 // v3.0 calibrtation
454 if (0 == dsr || 1 == dsr || 4 == dsr || 8 == dsr
455 || 9 == dsr || 12 == dsr || 16 == dsr
456 || 17 == dsr || 21 == dsr || 24 == dsr
457 || 25 == dsr || 29 == dsr)
458 azimuth_corrected_f += adjust_angle_four; // A4
459
460 if (2 == dsr || 3 == dsr || 6 == dsr || 10 == dsr
461 || 11 == dsr || 14 == dsr || 18 == dsr
462 || 19 == dsr || 23 == dsr || 26 == dsr
463 || 27 == dsr || 31 == dsr)
464 azimuth_corrected_f
465 += adjust_angle_three; // A3
466
467 if (5 == dsr || 13 == dsr || 20 == dsr || 28 == dsr)
468 azimuth_corrected_f += adjust_angle_two; // A2
469
470 if (7 == dsr || 15 == dsr || 22 == dsr || 30 == dsr)
471 azimuth_corrected_f += adjust_angle; // A1
472 } else if (
473 adjust_diff_one > 500 && adjust_diff_one < 660
474 && adjust_diff_two > 150
475 && adjust_diff_two < 350) {
476 // v2.7 calibrtation
477 if (10 == dsr || 14 == dsr || 18 == dsr
478 || 22 == dsr)
479 azimuth_corrected_f += adjust_angle_four; // A4
480
481 if (11 == dsr || 15 == dsr || 19 == dsr
482 || 23 == dsr)
483 azimuth_corrected_f
484 += adjust_angle_three; // A3
485
486 if (0 == dsr || 2 == dsr || 4 == dsr || 6 == dsr
487 || 8 == dsr || 12 == dsr || 16 == dsr
488 || 20 == dsr || 24 == dsr || 26 == dsr
489 || 28 == dsr || 30 == dsr)
490 azimuth_corrected_f += adjust_angle_two; // A2
491
492 if (1 == dsr || 3 == dsr || 5 == dsr || 7 == dsr
493 || 9 == dsr || 13 == dsr || 17 == dsr
494 || 21 == dsr || 25 == dsr || 27 == dsr
495 || 29 == dsr || 31 == dsr)
496 azimuth_corrected_f += adjust_angle; // A1
497 } else {
498 // v2.6 calibrtation
499 if (10 == dsr || 14 == dsr || 18 == dsr
500 || 22 == dsr)
501 azimuth_corrected_f += adjust_angle;
502
503 if (11 == dsr || 15 == dsr || 19 == dsr
504 || 23 == dsr)
505 azimuth_corrected_f -= adjust_angle;
506
507 if (0 == dsr || 2 == dsr || 4 == dsr || 6 == dsr
508 || 8 == dsr || 12 == dsr || 16 == dsr
509 || 20 == dsr || 24 == dsr || 26 == dsr
510 || 28 == dsr || 30 == dsr)
511 azimuth_corrected_f += adjust_angle_two;
512
513 if (1 == dsr || 3 == dsr || 5 == dsr || 7 == dsr
514 || 9 == dsr || 13 == dsr || 17 == dsr
515 || 21 == dsr || 25 == dsr || 27 == dsr
516 || 29 == dsr || 31 == dsr)
517 azimuth_corrected_f -= adjust_angle_two;
518 }
519 }
520
521 azimuth_corrected_f = azimuth_corrected_f < 0
522 ? azimuth_corrected_f + 36000
523 : azimuth_corrected_f;
524 azimuth_corrected_f = azimuth_corrected_f > 36000
525 ? azimuth_corrected_f - 36000
526 : azimuth_corrected_f;
527
528 if ((azimuth_corrected_f < config_.scan_start_angle())
529 || (azimuth_corrected_f > config_.scan_end_angle()))
530 continue;
531 if (packet_number == 0) {
532 if (azimuth_corrected_f > 30000) {
533 continue;
534 }
535 }
536
537 if (packet_number == packet_number_ - 1) {
538 if (azimuth_corrected_f < 10000) {
539 continue;
540 }
541 }
542
543 // 以结构为中心
544 float rotation_azimuth = ROTATION_RESOLUTION
545 * static_cast<float>(azimuth_corrected_f * M_PI)
546 / 180.0f;
547 azimuth_corrected_offset_f
548 = azimuth_corrected_f * ROTATION_RESOLUTION
549 - LSC32_AZIMUTH_TOFFSET;
550 float rotation_azimuth_offset
551 = static_cast<float>(
552 azimuth_corrected_offset_f * M_PI)
553 / 180.0f;
554
555 PointXYZIT* point = pc->add_point();
556 point->set_timestamp(point_time);
557 point->set_intensity(intensity);
558 point->set_intensity(intensity);
559
560 if (config_.calibration()) {
562 distance2,
563 &corrections,
564 static_cast<uint16_t>(azimuth_corrected_f),
565 point);
566 } else {
567 x = distance2 * cos_scan_altitude_caliration[dsr]
568 * cosf(rotation_azimuth)
569 + (LSC32_DISTANCE_TOFFSET
570 * cosf(rotation_azimuth_offset))
571 * DISTANCE_RESOLUTION;
572 y = -(distance2 * cos_scan_altitude_caliration[dsr]
573 * sinf(rotation_azimuth)
574 + (LSC32_DISTANCE_TOFFSET
575 * sinf(rotation_azimuth_offset))
576 * DISTANCE_RESOLUTION);
577 z = distance2 * sin_scan_altitude_caliration[dsr];
578
579 if ((y >= config_.bottom_left_x()
580 && y <= config_.top_right_x())
581 && (-x >= config_.bottom_left_y()
582 && -x <= config_.top_right_y())) {
583 point->set_x(nan);
584 point->set_y(nan);
585 point->set_z(nan);
586 point->set_timestamp(point_time);
587 point->set_intensity(0);
588 } else {
589 point->set_x(y);
590 point->set_y(-x);
591 point->set_z(z);
592 }
593 }
594 }
595 }
596 }
597 }
599}
600
601void Lslidar32Parser::Order(std::shared_ptr<PointCloud> cloud) {
602 int width = 32;
603 cloud->set_width(width);
604 int height = cloud->point_size() / cloud->width();
605 cloud->set_height(height);
606
607 std::shared_ptr<PointCloud> cloud_origin = std::make_shared<PointCloud>();
608 cloud_origin->CopyFrom(*cloud);
609
610 for (int i = 0; i < width; ++i) {
611 int col = ORDER_32[i];
612
613 for (int j = 0; j < height; ++j) {
614 // make sure offset is initialized, should be init at setup() just
615 // once
616 int target_index = j * width + i;
617 int origin_index = j * width + col;
618 cloud->mutable_point(target_index)
619 ->CopyFrom(cloud_origin->point(origin_index));
620 }
621 }
622}
623
624} // namespace parser
625} // namespace lslidar
626} // namespace drivers
627} // namespace apollo
std::map< int, LaserCorrection > laser_corrections_
Definition calibration.h:72
void GeneratePointcloud(const std::shared_ptr< apollo::drivers::lslidar::LslidarScan > &scan_msg, const std::shared_ptr< apollo::drivers::PointCloud > &out_msg)
void Order(std::shared_ptr< apollo::drivers::PointCloud > cloud)
double cos_scan_altitude_caliration[LSC32_SCANS_PER_FIRING]
void ComputeCoords(const float &raw_distance, LaserCorrection *corrections, const uint16_t rotation, PointXYZIT *point)
double sin_scan_altitude_caliration[LSC32_SCANS_PER_FIRING]
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
These classes Unpack raw Lslidar LIDAR packets into several useful formats.
constexpr int BLOCKS_PER_PACKET
Definition driver.h:37
struct apollo::drivers::lslidar::parser::raw_packet raw_packet_t
class register implement
Definition arena_queue.h:37