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

#include <lslidar_parser.h>

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

Public 成员函数

 LslidarCH64wParser (const Config &config)
 
 ~LslidarCH64wParser ()
 
void GeneratePointcloud (const std::shared_ptr< LslidarScan > &scan_msg, const std::shared_ptr< apollo::drivers::PointCloud > &out_msg)
 Set up for data processing.
 
void Order (std::shared_ptr< apollo::drivers::PointCloud > cloud)
 
- Public 成员函数 继承自 apollo::drivers::lslidar::parser::LslidarParser
 LslidarParser ()
 
 LslidarParser (const Config &config)
 
virtual ~LslidarParser ()
 
virtual void setup ()
 Set up for on-line operation.
 
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.h773 行定义.

构造及析构函数说明

◆ LslidarCH64wParser()

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

在文件 lslidarCH64w_parser.cc24 行定义.

24 :
25 LslidarParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
26 point_time_diff = 1 / (60.0 * 1000 * 32); // s
27 for (int i = 0; i < 4; ++i) {
28 prism_angle64[i] = i * 0.35;
29 }
30 for (int j = 0; j < 128; ++j) {
31 if (j / 4 % 2 == 0) {
32 theat1_s[j] = sin((-25 + floor(j / 8) * 2.5) * M_PI / 180);
33 theat2_s[j] = sin(prism_angle64[j % 4] * M_PI / 180);
34 theat1_c[j] = cos((-25 + floor(j / 8) * 2.5) * M_PI / 180);
35 theat2_c[j] = cos(prism_angle64[j % 4] * M_PI / 180);
36 } else {
37 theat1_s[j] = sin((-24 + floor(j / 8) * 2.5) * M_PI / 180);
38 theat2_s[j] = sin(prism_angle64[j % 4] * M_PI / 180);
39 theat1_c[j] = cos((-24 + floor(j / 8) * 2.5) * M_PI / 180);
40 theat2_c[j] = cos(prism_angle64[j % 4] * M_PI / 180);
41 }
42 }
43}
float cos(Angle16 a)
Definition angle.cc:42
float sin(Angle16 a)
Definition angle.cc:25

◆ ~LslidarCH64wParser()

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

在文件 lslidar_parser.h776 行定义.

776{}

成员函数说明

◆ GeneratePointcloud()

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

Set up for data processing.

Perform initializations needed before data processing can begin:

  • read device-specific angles calibration
参数
private_nhprivate node handle for ROS parameters
返回
0 if successful; errno value for failure

实现了 apollo::drivers::lslidar::parser::LslidarParser.

在文件 lslidarCH64w_parser.cc45 行定义.

47 {
48 // allocate a point cloud with same time and frame ID as raw data
49 out_msg->mutable_header()->set_timestamp_sec(
50 scan_msg->basetime() / 1000000000.0);
51 out_msg->mutable_header()->set_module_name(
52 scan_msg->header().module_name());
53 out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id());
54 out_msg->set_height(1);
55 out_msg->set_measurement_time(scan_msg->basetime() / 1000000000.0);
56 out_msg->mutable_header()->set_sequence_num(
57 scan_msg->header().sequence_num());
58 gps_base_usec_ = scan_msg->basetime();
59
60 packets_size = scan_msg->firing_pkts_size();
61 AINFO << "packets_size :" << packets_size;
62 for (size_t i = 0; i < packets_size; ++i) {
63 Unpack(static_cast<int>(i),
64 scan_msg->firing_pkts(static_cast<int>(i)),
65 out_msg);
66 last_time_stamp_ = out_msg->measurement_time();
67 ADEBUG << "stamp: " << std::fixed << last_time_stamp_;
68 }
69 if (out_msg->point().empty()) {
70 // we discard this pointcloud if empty
71 AERROR << "All points is NAN!Please check lslidar:" << config_.model();
72 }
73
74 // set default width
75 out_msg->set_width(out_msg->point_size());
76}
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42

◆ Order()

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

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