25 LslidarParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {}
28 const std::shared_ptr<LslidarScan> &scan_msg,
29 const std::shared_ptr<PointCloud> &out_msg) {
31 out_msg->mutable_header()->set_timestamp_sec(
32 scan_msg->basetime() / 1000000000.0);
33 out_msg->mutable_header()->set_module_name(
34 scan_msg->header().module_name());
35 out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id());
36 out_msg->set_height(1);
37 out_msg->set_measurement_time(scan_msg->basetime() / 1000000000.0);
38 out_msg->mutable_header()->set_sequence_num(
39 scan_msg->header().sequence_num());
40 gps_base_usec_ = scan_msg->basetime();
42 packets_size = scan_msg->firing_pkts_size();
44 for (
size_t i = 0; i < packets_size; ++i) {
45 Unpack(
static_cast<int>(i),
46 scan_msg->firing_pkts(
static_cast<int>(i)),
52 if (out_msg->point().empty()) {
58 out_msg->set_width(out_msg->point_size());
65void LslidarCH32Parser::Unpack(
68 std::shared_ptr<PointCloud> pc) {
70 uint64_t packet_end_time;
71 double z_sin_altitude = 0.0;
72 double z_cos_altitude = 0.0;
76 packet_end_time = pkt.
stamp();
78 for (
size_t point_idx = 0; point_idx < POINTS_PER_PACKET; point_idx++) {
89 point_distance.
bytes[3] = 0;
90 firings[point_idx].
distance =
static_cast<double>(point_distance.
uint)
91 * DISTANCE_RESOLUTION2;
95 double scan_laser_altitude_degree[8];
97 for (
int i = 0; i < 8; i++)
98 scan_laser_altitude_degree[i] = sin_scan_laser_altitude[i];
100 for (
int i = 0; i < 8; i++)
101 scan_laser_altitude_degree[i] = sin_scan_laser_altitude_ch32[i];
104 for (
size_t point_idx = 0; point_idx < POINTS_PER_PACKET; point_idx++) {
105 LaserCorrection &corrections
110 firings[point_idx].distance
111 = firings[point_idx].distance + corrections.dist_correction;
118 double cos_azimuth_half = cos(firings[point_idx].azimuth * 0.5);
119 z_sin_altitude = scan_laser_altitude_degree
121 + 2 * cos_azimuth_half
122 * sin_scan_mirror_altitude
124 z_cos_altitude = sqrt(1 - z_sin_altitude * z_sin_altitude);
126 x = firings[point_idx].distance * z_cos_altitude
127 * cos(firings[point_idx].azimuth);
128 y = firings[point_idx].distance * z_cos_altitude
129 * sin(firings[point_idx].azimuth);
130 z = firings[point_idx].distance * z_sin_altitude;
134 = packet_end_time - 1665 * (POINTS_PER_PACKET - point_idx - 1);
135 if (time_last < point_time && time_last > 0) {
136 point_time = time_last + 1665;
138 time_last = point_time;
140 PointXYZIT *point = pc->add_point();
141 (point_time / 1000000000.0);
142 point->set_intensity(firings[point_idx].intensity);
146 firings[point_idx].vertical_line,
148 firings[point_idx].distance,
150 firings[point_idx].azimuth,
159 point->set_timestamp(point_time);
160 point->set_intensity(0);
172 cloud->set_width(width);
173 int height = cloud->point_size() / cloud->width();
174 cloud->set_height(height);
176 std::shared_ptr<PointCloud> cloud_origin = std::make_shared<PointCloud>();
177 cloud_origin->CopyFrom(*cloud);
179 for (
int i = 0; i < width; ++i) {
182 for (
int j = 0; j < height; ++j) {
185 int target_index = j * width + i;
186 int origin_index = j * width + col;
187 cloud->mutable_point(target_index)
188 ->CopyFrom(cloud_origin->point(origin_index));
std::map< int, LaserCorrection > laser_corrections_
void GeneratePointcloud(const std::shared_ptr< LslidarScan > &scan_msg, const std::shared_ptr< apollo::drivers::PointCloud > &out_msg)
Set up for data processing.
LslidarCH32Parser(const Config &config)
void Order(std::shared_ptr< apollo::drivers::PointCloud > cloud)
Lslidar data conversion class
void ComputeCoords2(int Laser_ring, int Type, const float &raw_distance, LaserCorrection *corrections, const double rotation, PointXYZIT *point)
These classes Unpack raw Lslidar LIDAR packets into several useful formats.
optional float bottom_left_y
optional float top_right_x
optional uint32 degree_mode
optional float top_right_y
optional bool calibration
optional float bottom_left_x
Point points[POINTS_PER_PACKET]
used for unpacking the first two data bytes in a block