Point Cloud Library (PCL) 1.12.0
|
A point structure representing Euclidean xyz coordinates, and the intensity value. More...
#include <pcl/impl/point_types.hpp>
Public Attributes | ||
PCL_ADD_POINT4D | ||
union { | ||
struct { | ||
float intensity | ||
} | ||
float data_c [4] | ||
}; | ||
A point structure representing Euclidean xyz coordinates, and the intensity value.
Definition at line 495 of file point_types.hpp.
union { ... } pcl::_PointXYZI |
float pcl::_PointXYZI::data_c[4] |
Definition at line 504 of file point_types.hpp.
float pcl::_PointXYZI::intensity |
Definition at line 502 of file point_types.hpp.
Referenced by pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::Edge< PointInT, PointInT >::detectEdgeCanny(), pcl::PointXYZI::PointXYZI(), pcl::PointXYZI::PointXYZI(), and pcl::PointXYZRGBtoXYZI().
pcl::_PointXYZI::PCL_ADD_POINT4D |
Definition at line 497 of file point_types.hpp.