Apollo 10.0
自动驾驶开放平台
apollo::drivers::velodyne::Velodyne128Parser类 参考

#include <velodyne_parser.h>

类 apollo::drivers::velodyne::Velodyne128Parser 继承关系图:
apollo::drivers::velodyne::Velodyne128Parser 的协作图:

Public 成员函数

 Velodyne128Parser (const Config &config)
 
 ~Velodyne128Parser ()
 
void GeneratePointcloud (const std::shared_ptr< VelodyneScan > &scan_msg, std::shared_ptr< PointCloud > out_msg)
 Set up for data processing.
 
void Order (std::shared_ptr< PointCloud > cloud)
 
- Public 成员函数 继承自 apollo::drivers::velodyne::VelodyneParser
 VelodyneParser ()
 
 VelodyneParser (const Config &config)
 
virtual ~VelodyneParser ()
 
virtual void setup ()
 Set up for on-line operation.
 
const Calibrationget_calibration ()
 
const double get_last_timestamp ()
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::drivers::velodyne::VelodyneParser
PointXYZIT get_nan_point (uint64_t timestamp)
 
void init_angle_params (double view_direction, double view_width)
 
void ComputeCoords (const float &raw_distance, const LaserCorrection &corrections, const uint16_t rotation, PointXYZIT *point)
 Compute coords with the data in block
 
bool is_scan_valid (int rotation, float distance)
 
uint64_t GetGpsStamp (double current_stamp, double *previous_stamp, uint64_t *gps_base_usec)
 
- Protected 属性 继承自 apollo::drivers::velodyne::VelodyneParser
const float(* inner_time_ )[12][32]
 
Calibration calibration_
 
float sin_rot_table_ [ROTATION_MAX_UNITS]
 
float cos_rot_table_ [ROTATION_MAX_UNITS]
 
double last_time_stamp_
 
Config config_
 
bool need_two_pt_correction_
 
Mode mode_
 

详细描述

在文件 velodyne_parser.h355 行定义.

构造及析构函数说明

◆ Velodyne128Parser()

apollo::drivers::velodyne::Velodyne128Parser::Velodyne128Parser ( const Config config)
explicit

在文件 velodyne128_parser.cc23 行定义.

◆ ~Velodyne128Parser()

apollo::drivers::velodyne::Velodyne128Parser::~Velodyne128Parser ( )
inline

在文件 velodyne_parser.h358 行定义.

358{}

成员函数说明

◆ GeneratePointcloud()

void apollo::drivers::velodyne::Velodyne128Parser::GeneratePointcloud ( const std::shared_ptr< VelodyneScan > &  scan_msg,
std::shared_ptr< 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::velodyne::VelodyneParser.

在文件 velodyne128_parser.cc29 行定义.

31 {
32 // allocate a point cloud with same time and frame ID as raw data
33 out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id());
34 out_msg->mutable_header()->set_timestamp_sec(cyber::Time().Now().ToSecond());
35 out_msg->set_height(1);
36
37 // us
38 gps_base_usec_ = scan_msg->basetime();
39
40 for (int i = 0; i < scan_msg->firing_pkts_size(); ++i) {
41 Unpack(scan_msg->firing_pkts(i), out_msg);
42 last_time_stamp_ = out_msg->measurement_time();
43 }
44
45 size_t size = out_msg->point_size();
46 if (size == 0) {
47 // we discard this pointcloud if empty
48 AERROR << "All points is NAN!Please check velodyne:" << config_.model();
49 return;
50 } else {
51 const auto timestamp =
52 out_msg->point(static_cast<int>(size) - 1).timestamp();
53 out_msg->set_measurement_time(static_cast<double>(timestamp) / 1e9);
54 out_msg->mutable_header()->set_lidar_timestamp(timestamp);
55 }
56 out_msg->set_width(out_msg->point_size());
57}
#define AERROR
Definition log.h:44

◆ Order()

void apollo::drivers::velodyne::Velodyne128Parser::Order ( std::shared_ptr< PointCloud cloud)
virtual

实现了 apollo::drivers::velodyne::VelodyneParser.

在文件 velodyne128_parser.cc67 行定义.

67 {
68 (void)cloud;
69}

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