Apollo 10.0
自动驾驶开放平台
apollo::localization::msf::PCDExporter类 参考

Export pcd from rosbag. 更多...

#include <pcd_exporter.h>

apollo::localization::msf::PCDExporter 的协作图:

Public 成员函数

 PCDExporter (const std::string &pcd_folder)
 
 ~PCDExporter ()
 
void CompensatedPcdCallback (const std::string &msg)
 

详细描述

Export pcd from rosbag.

在文件 pcd_exporter.h31 行定义.

构造及析构函数说明

◆ PCDExporter()

apollo::localization::msf::PCDExporter::PCDExporter ( const std::string &  pcd_folder)
explicit

在文件 pcd_exporter.cc28 行定义.

28 {
29 pcd_folder_ = pcd_folder;
30 std::string stamp_file = pcd_folder_ + "/pcd_timestamp.txt";
31
32 if ((stamp_file_handle_ = fopen(stamp_file.c_str(), "a")) == nullptr) {
33 AERROR << "Cannot open stamp file!";
34 }
35}
#define AERROR
Definition log.h:44

◆ ~PCDExporter()

apollo::localization::msf::PCDExporter::~PCDExporter ( )

在文件 pcd_exporter.cc37 行定义.

37 {
38 if (stamp_file_handle_ != nullptr) {
39 fclose(stamp_file_handle_);
40 }
41}

成员函数说明

◆ CompensatedPcdCallback()

void apollo::localization::msf::PCDExporter::CompensatedPcdCallback ( const std::string &  msg)

在文件 pcd_exporter.cc43 行定义.

43 {
44 AINFO << "Compensated pcd callback.";
45 drivers::PointCloud msg;
46 msg.ParseFromString(msg_string);
47
48 static unsigned int index = 1;
49
50 std::stringstream ss_pcd;
51 ss_pcd << pcd_folder_ << "/" << index << ".pcd";
52 std::string pcd_filename = ss_pcd.str();
53
54 WritePcdFile(pcd_filename, msg);
55 double timestamp = cyber::Time(msg.measurement_time()).ToSecond();
56 fprintf(stamp_file_handle_, "%u %lf\n", index, timestamp);
57
58 ++index;
59}
#define AINFO
Definition log.h:42

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