25 LslidarParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
30 const std::shared_ptr<LslidarScan>& scan_msg,
31 const std::shared_ptr<PointCloud>& out_msg) {
33 out_msg->mutable_header()->set_timestamp_sec(
34 scan_msg->basetime() / 1000000000.0);
35 out_msg->mutable_header()->set_module_name(
36 scan_msg->header().module_name());
37 out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id());
38 out_msg->set_height(1);
39 out_msg->set_measurement_time(scan_msg->basetime() / 1000000000.0);
40 out_msg->mutable_header()->set_sequence_num(
41 scan_msg->header().sequence_num());
42 gps_base_usec_ = scan_msg->basetime();
44 packets_size = scan_msg->firing_pkts_size();
46 for (
size_t i = 0; i < packets_size; ++i) {
47 Unpack(
static_cast<int>(i),
48 scan_msg->firing_pkts(
static_cast<int>(i)),
54 if (out_msg->point().empty()) {
59 out_msg->set_width(out_msg->point_size());
66void LslidarCH120Parser::Unpack(
69 std::shared_ptr<PointCloud> pc) {
71 uint64_t packet_end_time;
72 double z_sin_altitude = 0.0;
73 double z_cos_altitude = 0.0;
77 packet_end_time = pkt.
stamp();
79 for (
int point_idx1 = 0; point_idx1 < POINTS_PER_PACKET; point_idx1++) {
91 point_distance.
bytes[3] = 0;
92 firings[point_idx1].
distance =
static_cast<double>(point_distance.
uint)
93 * DISTANCE_RESOLUTION2;
97 for (
int point_idx = 0; point_idx < POINTS_PER_PACKET; point_idx++) {
98 LaserCorrection& corrections
103 firings[point_idx].distance
104 = firings[point_idx].distance + corrections.dist_correction;
110 z_sin_altitude = sin(
111 (-13 + 0.167 * firings[point_idx].vertical_line) *
DEG_TO_RAD);
112 z_cos_altitude = sqrt(1 - z_sin_altitude * z_sin_altitude);
113 x = firings[point_idx].
distance * z_cos_altitude
114 * cos(firings[point_idx].azimuth);
115 y = firings[point_idx].
distance * z_cos_altitude
116 * sin(firings[point_idx].azimuth);
117 z = firings[point_idx].
distance * z_sin_altitude;
121 = packet_end_time - 1282 * (POINTS_PER_PACKET - point_idx - 1);
122 if (time_last < point_time && time_last > 0) {
123 point_time = time_last + 1282;
125 time_last = point_time;
128 point->set_timestamp(point_time);
129 point->set_intensity(firings[point_idx].intensity);
133 firings[point_idx].vertical_line,
135 firings[point_idx].distance,
137 firings[point_idx].azimuth,
147 point->set_timestamp(point_time);
148 point->set_intensity(0);
std::map< int, LaserCorrection > laser_corrections_
void Order(std::shared_ptr< PointCloud > cloud)
void GeneratePointcloud(const std::shared_ptr< LslidarScan > &scan_msg, const std::shared_ptr< PointCloud > &out_msg)
LslidarCH120Parser(const Config &config)
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 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