Apollo 10.0
自动驾驶开放平台
apollo::drivers::lslidar::parser::LslidarCH128X1Parser类 参考

#include <lslidar_parser.h>

类 apollo::drivers::lslidar::parser::LslidarCH128X1Parser 继承关系图:
apollo::drivers::lslidar::parser::LslidarCH128X1Parser 的协作图:

Public 成员函数

 LslidarCH128X1Parser (const Config &config)
 
 ~LslidarCH128X1Parser ()
 
void GeneratePointcloud (const std::shared_ptr< LslidarScan > &scan_msg, const std::shared_ptr< PointCloud > &out_msg)
 
void Order (std::shared_ptr< PointCloud > cloud)
 
- Public 成员函数 继承自 apollo::drivers::lslidar::parser::LslidarParser
 LslidarParser ()
 
 LslidarParser (const Config &config)
 
virtual ~LslidarParser ()
 
virtual void GeneratePointcloud (const std::shared_ptr< LslidarScan > &scan_msg, const std::shared_ptr< apollo::drivers::PointCloud > &out_msg)=0
 Set up for data processing.
 
virtual void setup ()
 Set up for on-line operation.
 
virtual void Order (std::shared_ptr< apollo::drivers::PointCloud > cloud)=0
 
const double get_last_timestamp ()
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::drivers::lslidar::parser::LslidarParser
bool is_scan_valid (int rotation, float distance)
 
void ComputeCoords (const float &raw_distance, LaserCorrection *corrections, const uint16_t rotation, PointXYZIT *point)
 
void ComputeCoords2 (int Laser_ring, int Type, const float &raw_distance, LaserCorrection *corrections, const double rotation, PointXYZIT *point)
 
- Protected 属性 继承自 apollo::drivers::lslidar::parser::LslidarParser
double scan_altitude [16]
 
float sin_azimuth_table [ROTATION_MAX_UNITS]
 
float cos_azimuth_table [ROTATION_MAX_UNITS]
 
double cos_scan_altitude_caliration [LSC32_SCANS_PER_FIRING]
 
double sin_scan_altitude_caliration [LSC32_SCANS_PER_FIRING]
 
double last_time_stamp_
 
double theat1_s [128]
 
double theat2_s [128]
 
double theat1_c [128]
 
double theat2_c [128]
 
double prism_angle [4]
 
double prism_angle64 [4]
 
Config config_
 
Calibration calibration_
 
bool need_two_pt_correction_
 
bool config_vert_angle
 
uint64_t current_packet_time = 0
 
uint64_t previous_packet_time = 0
 

详细描述

在文件 lslidar_parser.h861 行定义.

构造及析构函数说明

◆ LslidarCH128X1Parser()

apollo::drivers::lslidar::parser::LslidarCH128X1Parser::LslidarCH128X1Parser ( const Config config)
explicit

在文件 lslidarCH128X1_parser.cc24 行定义.

24 :
25 LslidarParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {}

◆ ~LslidarCH128X1Parser()

apollo::drivers::lslidar::parser::LslidarCH128X1Parser::~LslidarCH128X1Parser ( )
inline

在文件 lslidar_parser.h864 行定义.

864{}

成员函数说明

◆ GeneratePointcloud()

void apollo::drivers::lslidar::parser::LslidarCH128X1Parser::GeneratePointcloud ( const std::shared_ptr< LslidarScan > &  scan_msg,
const std::shared_ptr< PointCloud > &  out_msg 
)

在文件 lslidarCH128X1_parser.cc27 行定义.

29 {
30 // allocate a point cloud with same time and frame ID as raw data
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();
41
42 const unsigned char* difop_ptr
43 = (const unsigned char*)scan_msg->difop_pkts(0).data().c_str();
44
45 two_bytes angle_1, angle_2, angle_3, angle_4;
46 angle_1.bytes[0] = difop_ptr[243];
47 angle_1.bytes[1] = difop_ptr[242];
48 prism_angle[0] = angle_1.uint * 0.01;
49
50 angle_2.bytes[0] = difop_ptr[245];
51 angle_2.bytes[1] = difop_ptr[244];
52 prism_angle[1] = angle_2.uint * 0.01;
53
54 angle_3.bytes[0] = difop_ptr[247];
55 angle_3.bytes[1] = difop_ptr[246];
56 prism_angle[2] = angle_3.uint * 0.01;
57
58 angle_4.bytes[0] = difop_ptr[249];
59 angle_4.bytes[1] = difop_ptr[248];
60 prism_angle[3] = angle_4.uint * 0.01;
61
62 packets_size = scan_msg->firing_pkts_size();
63
64 for (size_t i = 0; i < packets_size; ++i) {
65 Unpack(static_cast<int>(i),
66 scan_msg->firing_pkts(static_cast<int>(i)),
67 out_msg);
68 last_time_stamp_ = out_msg->measurement_time();
69 ADEBUG << "stamp: " << std::fixed << last_time_stamp_;
70 }
71
72 AINFO << "packets_size :" << packets_size;
73 if (out_msg->point().empty()) {
74 // we discard this pointcloud if empty
75 AERROR << "All points is NAN!Please check lslidar:" << config_.model();
76 }
77
78 // set default width
79 out_msg->set_width(out_msg->point_size());
80}
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42

◆ Order()

void apollo::drivers::lslidar::parser::LslidarCH128X1Parser::Order ( std::shared_ptr< PointCloud cloud)

在文件 lslidarCH128X1_parser.cc212 行定义.

212{}

该类的文档由以下文件生成: