Apollo  v5.5.0
Open source self driving car software
pcl_util.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <string>
19 
20 #include "pcl/io/pcd_io.h"
21 
24 
25 namespace apollo {
26 namespace perception {
27 namespace lidar {
28 
29 typedef pcl::PointXYZRGB CPoint;
30 typedef pcl::PointCloud<CPoint> CPointCloud;
31 typedef pcl::PointCloud<CPoint>::Ptr CPointCloudPtr;
32 typedef pcl::PointCloud<CPoint>::ConstPtr CPointCloudConstPtr;
33 
34 struct PCLPointXYZIT {
35  float x;
36  float y;
37  float z;
38  uint8_t intensity;
39  double timestamp;
40  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 
43 struct PCLPointXYZL {
44  float x;
45  float y;
46  float z;
47  uint32_t label;
48  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 
51 inline bool LoadPCLPCD(const std::string& file_path,
52  base::PointFCloud* cloud_out) {
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;
56  return false;
57  }
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);
62  new_pt.x = pt.x;
63  new_pt.y = pt.y;
64  new_pt.z = pt.z;
65  new_pt.intensity = pt.intensity;
66  cloud_out->mutable_points_timestamp()->at(i) = pt.timestamp;
67  }
68  return true;
69 }
70 
71 // static bool WritePcd(const std::string& file_path,
72 // const base::PointFCloud& cloud) {
73 // pcl::PointCloud<PCLPointXYZL> pcl_cloud;
74 // for (size_t i = 0; i < cloud.size(); ++i) {
75 // PCLPointXYZL point;
76 // point.x = cloud[i].x;
77 // point.y = cloud[i].y;
78 // point.z = cloud[i].z;
79 // point.label = cloud.points_label().at(i);
80 // pcl_cloud.push_back(point);
81 // }
82 // try {
83 // pcl::PCDWriter writer;
84 // writer.writeBinaryCompressed(file_path, pcl_cloud);
85 // } catch (const pcl::IOException& ex) {
86 // AERROR << ex.detailedMessage();
87 // return false;
88 // }
89 // return true;
90 // }
91 //
92 } // namespace lidar
93 } // namespace perception
94 } // namespace apollo
95 
96 POINT_CLOUD_REGISTER_POINT_STRUCT(apollo::perception::lidar::PCLPointXYZIT,
97  (float, x, x)(float, y, y)(float, z, z)(
98  uint8_t, intensity,
99  intensity)(double, timestamp, timestamp))
100 
101 POINT_CLOUD_REGISTER_POINT_STRUCT(apollo::perception::lidar::PCLPointXYZL,
102  (float, x, x)(float, y, y)(float, z,
103  z)(uint32_t, label,
104  label))
void resize(const size_t size) override
Definition: point_cloud.h:317
uint8_t intensity
Definition: pcl_util.h:38
float z
Definition: pcl_util.h:37
float y
Definition: pcl_util.h:36
pcl::PointXYZRGB CPoint
Definition: pcl_util.h:29
Definition: blob.h:72
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
uint32_t label
Definition: pcl_util.h:47
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