20 #include "pcl/io/pcd_io.h" 26 namespace perception {
40 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 pcl::PointCloud<PCLPointXYZIT> org_cloud;
54 if (pcl::io::loadPCDFile(file_path, org_cloud) < 0) {
55 AERROR <<
"Failed to load pcd file " << file_path;
58 cloud_out->
resize(org_cloud.size());
59 for (
size_t i = 0; i < org_cloud.size(); ++i) {
60 auto& pt = org_cloud.points[i];
61 auto& new_pt = cloud_out->
at(i);
65 new_pt.intensity = pt.intensity;
97 (
float,
x,
x)(
float,
y,
y)(
float,
z,
z)(
102 (
float,
x,
x)(
float,
y,
y)(
float,
z,
void resize(const size_t size) override
Definition: point_cloud.h:317
uint8_t intensity
Definition: pcl_util.h:38
Definition: pcl_util.h:43
float z
Definition: pcl_util.h:37
float y
Definition: pcl_util.h:36
pcl::PointXYZRGB CPoint
Definition: pcl_util.h:29
pcl::PointCloud< CPoint >::Ptr CPointCloudPtr
Definition: pcl_util.h:31
pcl::PointCloud< CPoint > CPointCloud
Definition: pcl_util.h:30
pcl::PointCloud< CPoint >::ConstPtr CPointCloudConstPtr
Definition: pcl_util.h:32
double timestamp
Definition: pcl_util.h:39
float x
Definition: pcl_util.h:44
Definition: point_cloud.h:257
uint32_t label
Definition: pcl_util.h:47
Definition: pcl_util.h:34
float z
Definition: pcl_util.h:46
struct apollo::perception::lidar::PCLPointXYZIT EIGEN_ALIGN16
float y
Definition: pcl_util.h:45
std::vector< double > * mutable_points_timestamp()
Definition: point_cloud.h:438
bool LoadPCLPCD(const std::string &file_path, base::PointFCloud *cloud_out)
Definition: pcl_util.h:51
float x
Definition: pcl_util.h:35
const PointT * at(size_t col, size_t row) const
Definition: point_cloud.h:57