25 LslidarParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
28 adjust_angle_three = 0;
29 adjust_angle_four = 0;
36 const std::shared_ptr<LslidarScan>& scan_msg,
37 const std::shared_ptr<PointCloud>& out_msg) {
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();
50 double scan_altitude_original_degree33[32];
51 double scan_altitude_original_degree1[32];
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) {
64 = (difop_ptr[186] * 256
66 if (adjust_angle > 32767) {
67 adjust_angle = adjust_angle - 65535;
70 = (difop_ptr[190] * 256
72 if (adjust_angle_two > 32767) {
73 adjust_angle_two = adjust_angle_two - 65535;
76 = (difop_ptr[188] * 256
78 if (adjust_angle_three > 32767) {
79 adjust_angle_three = adjust_angle_three - 65535;
82 = (difop_ptr[192] * 256
84 if (adjust_angle_four > 32767) {
85 adjust_angle_four = adjust_angle_four - 65535;
87 memcpy(scan_altitude_original_degree1,
88 scan_altitude_original_A3,
90 memcpy(scan_altitude_original_degree33,
91 scan_altitude_original_C3,
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);
98 if (difop_ptr[1195] == 0x21)
103 config_.set_distance_unit(0.4f);
105 for (
int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
110 scan_altitude_original_A3[i] * M_PI)
114 scan_altitude_original_A3[i] * M_PI)
116 scan_altitude_A[i] = scan_altitude_original_A3[i];
122 scan_altitude_original_C3[i] * M_PI)
126 scan_altitude_original_C3[i] * M_PI)
128 scan_altitude_C[i] = scan_altitude_original_C3[i];
137 = (difop_ptr[34] * 256
139 if (adjust_angle > 32767) {
140 adjust_angle = adjust_angle - 65535;
143 = (difop_ptr[42] * 256
145 if (adjust_angle_two > 32767) {
146 adjust_angle_two = adjust_angle_two - 65535;
149 = (difop_ptr[66] * 256
151 if (adjust_angle_three > 32767) {
152 adjust_angle_three = adjust_angle_three - 65535;
155 = (difop_ptr[68] * 256
157 if (adjust_angle_four > 32767) {
158 adjust_angle_four = adjust_angle_four - 65535;
160 AWARN <<
"Load config failed, config file";
162 for (
int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
167 scan_altitude_original_A[i] * M_PI)
171 scan_altitude_original_A[i] * M_PI)
173 scan_altitude_A[i] = scan_altitude_original_A[i];
179 scan_altitude_original_C[i] * M_PI)
183 scan_altitude_original_C[i] * M_PI)
185 scan_altitude_C[i] = scan_altitude_original_C[i];
188 memcpy(scan_altitude_original_degree1,
189 scan_altitude_original_A,
191 memcpy(scan_altitude_original_degree33,
192 scan_altitude_original_C,
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;
209 =
static_cast<double>(vert_angle * ROTATION_RESOLUTION);
210 if (fabs(scan_altitude_original_degree1[i] - scan_altitude_A[i])
212 scan_altitude_A[i] = scan_altitude_original_degree1[i];
219 =
static_cast<double>(vert_angle * ROTATION_RESOLUTION);
220 if (fabs(scan_altitude_original_degree33[i]
221 - scan_altitude_C[i])
223 scan_altitude_C[i] = scan_altitude_original_degree33[i];
230 size_t packets_size = scan_msg->firing_pkts_size();
232 packet_number_ = packets_size;
234 AINFO <<
"packets_size :" << packets_size;
236 for (
size_t i = 0; i < packets_size; ++i) {
237 Unpack(scan_msg->firing_pkts(
static_cast<int>(i)), out_msg, i);
242 if (out_msg->point().empty()) {
248 out_msg->set_width(out_msg->point_size());
255void Lslidar32Parser::Unpack(
257 std::shared_ptr<PointCloud> pc,
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;
266 uint64_t packet_end_time;
269 for (
int i = 0; i < LSC32_SCANS_PER_FIRING; i++) {
273 static_cast<float>(scan_altitude_A[i] * M_PI) / 180.0f);
275 static_cast<float>(scan_altitude_A[i] * M_PI) / 180.0f);
281 static_cast<float>(scan_altitude_C[i] * M_PI) / 180.0f);
283 static_cast<float>(scan_altitude_C[i] * M_PI) / 180.0f);
291 packet_end_time = pkt.
stamp();
293 packet_end_time = pkt.
stamp();
297 int point_count = -1;
299 if (UPPER_BANK != raw->blocks[block].header)
302 azimuth =
static_cast<float>(
303 256 * raw->blocks[block].rotation_2
304 + raw->blocks[block].rotation_1);
307 if (block < (BLOCKS_PER_PACKET - 2)) {
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;
314 =
static_cast<float>((36000 + azi1 - azi2) % 36000);
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;
322 =
static_cast<float>((36000 + azi1 - azi2) % 36000);
325 = azimuth_diff < 0 ? azimuth_diff + 36000 : azimuth_diff;
326 azimuth_diff = azimuth_diff > 36000 ? azimuth_diff - 36000
329 if (block < (BLOCKS_PER_PACKET - 1)) {
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;
336 =
static_cast<float>((36000 + azi1 - azi2) % 36000);
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;
344 =
static_cast<float>((36000 + azi1 - azi2) % 36000);
347 = azimuth_diff < 0 ? azimuth_diff + 36000 : azimuth_diff;
348 azimuth_diff = azimuth_diff > 36000 ? azimuth_diff - 36000
352 for (
int firing = 0, k = 0; firing < LSC32_FIRINGS_PER_BLOCK;
354 for (
int dsr = 0; dsr < LSC32_SCANS_PER_FIRING;
355 ++dsr, k += RAW_SCAN_SIZE) {
359 LaserCorrection& corrections
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;
373 tmp.bytes[0] = raw->blocks[block].data[k];
374 tmp.bytes[1] = raw->blocks[block].data[k + 1];
375 int distance = tmp.uint;
378 intensity = raw->blocks[block].data[k + 2];
380 float distance2 = (distance * DISTANCE_RESOLUTION)
384 distance2 = distance2 + corrections.dist_correction;
389 - (SCANS_PER_PACKET - point_count - 1)
392 / (SCANS_PER_PACKET);
400 - (SCANS_PER_PACKET - point_count - 1)
403 / (SCANS_PER_PACKET);
411 PointXYZIT* point = pc->add_point();
415 point->set_timestamp(point_time);
416 point->set_intensity(0);
420 double adjust_diff = adjust_angle_two - adjust_angle;
421 if (adjust_diff > 300 && adjust_diff < 460) {
423 if (lslidar_type == 3) {
425 azimuth_corrected_f += adjust_angle_two;
427 azimuth_corrected_f += adjust_angle;
431 azimuth_corrected_f += adjust_angle_two;
433 azimuth_corrected_f += adjust_angle;
439 azimuth_corrected_f += adjust_angle;
441 azimuth_corrected_f -= adjust_angle;
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) {
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;
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)
465 += adjust_angle_three;
467 if (5 == dsr || 13 == dsr || 20 == dsr || 28 == dsr)
468 azimuth_corrected_f += adjust_angle_two;
470 if (7 == dsr || 15 == dsr || 22 == dsr || 30 == dsr)
471 azimuth_corrected_f += adjust_angle;
473 adjust_diff_one > 500 && adjust_diff_one < 660
474 && adjust_diff_two > 150
475 && adjust_diff_two < 350) {
477 if (10 == dsr || 14 == dsr || 18 == dsr
479 azimuth_corrected_f += adjust_angle_four;
481 if (11 == dsr || 15 == dsr || 19 == dsr
484 += adjust_angle_three;
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;
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;
499 if (10 == dsr || 14 == dsr || 18 == dsr
501 azimuth_corrected_f += adjust_angle;
503 if (11 == dsr || 15 == dsr || 19 == dsr
505 azimuth_corrected_f -= adjust_angle;
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;
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;
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;
531 if (packet_number == 0) {
532 if (azimuth_corrected_f > 30000) {
537 if (packet_number == packet_number_ - 1) {
538 if (azimuth_corrected_f < 10000) {
544 float rotation_azimuth = ROTATION_RESOLUTION
545 *
static_cast<float>(azimuth_corrected_f * M_PI)
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)
555 PointXYZIT* point = pc->add_point();
556 point->set_timestamp(point_time);
557 point->set_intensity(intensity);
558 point->set_intensity(intensity);
564 static_cast<uint16_t
>(azimuth_corrected_f),
568 * cosf(rotation_azimuth)
569 + (LSC32_DISTANCE_TOFFSET
570 * cosf(rotation_azimuth_offset))
571 * DISTANCE_RESOLUTION;
573 * sinf(rotation_azimuth)
574 + (LSC32_DISTANCE_TOFFSET
575 * sinf(rotation_azimuth_offset))
576 * DISTANCE_RESOLUTION);
586 point->set_timestamp(point_time);
587 point->set_intensity(0);
603 cloud->set_width(width);
604 int height = cloud->point_size() / cloud->width();
605 cloud->set_height(height);
607 std::shared_ptr<PointCloud> cloud_origin = std::make_shared<PointCloud>();
608 cloud_origin->CopyFrom(*cloud);
610 for (
int i = 0; i < width; ++i) {
613 for (
int j = 0; j < height; ++j) {
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));
std::map< int, LaserCorrection > laser_corrections_
void GeneratePointcloud(const std::shared_ptr< apollo::drivers::lslidar::LslidarScan > &scan_msg, const std::shared_ptr< apollo::drivers::PointCloud > &out_msg)
Lslidar32Parser(const Config &config)
void Order(std::shared_ptr< apollo::drivers::PointCloud > cloud)
Lslidar data conversion class
double cos_scan_altitude_caliration[LSC32_SCANS_PER_FIRING]
uint64_t current_packet_time
uint64_t previous_packet_time
void ComputeCoords(const float &raw_distance, LaserCorrection *corrections, const uint16_t rotation, PointXYZIT *point)
double sin_scan_altitude_caliration[LSC32_SCANS_PER_FIRING]
These classes Unpack raw Lslidar LIDAR packets into several useful formats.
constexpr int BLOCKS_PER_PACKET
struct apollo::drivers::lslidar::parser::raw_packet raw_packet_t
optional float bottom_left_y
optional uint32 return_mode
optional float scan_end_angle
optional float top_right_x
optional uint32 degree_mode
optional float top_right_y
optional bool calibration
optional float distance_unit
optional float bottom_left_x
optional bool time_synchronization
optional bool config_vert
optional float scan_start_angle