Point Cloud Library (PCL) 1.15.1
Loading...
Searching...
No Matches
pcl::PointXYZI Struct Reference

#include <pcl/impl/point_types.hpp>

Inheritance diagram for pcl::PointXYZI:

Public Member Functions

constexpr PointXYZI (const _PointXYZI &p)
constexpr PointXYZI (float _intensity=0.f)
constexpr PointXYZI (float _x, float _y, float _z, float _intensity=0.f)

Friends

std::ostream & operator<< (std::ostream &os, const PointXYZI &p)

Additional Inherited Members

Public Attributes inherited from pcl::_PointXYZI
union { 
   struct { 
      float   intensity 
   } 
   float   data_c [4] 
}; 

Detailed Description

Definition at line 456 of file point_types.hpp.

Constructor & Destructor Documentation

◆ PointXYZI() [1/3]

pcl::PointXYZI::PointXYZI ( const _PointXYZI & p)
inlineconstexpr

Definition at line 458 of file point_types.hpp.

References pcl::_PointXYZI::intensity, and PointXYZI().

Referenced by operator<<, PointXYZI(), and PointXYZI().

◆ PointXYZI() [2/3]

pcl::PointXYZI::PointXYZI ( float _intensity = 0.f)
inlineconstexpr

Definition at line 460 of file point_types.hpp.

References PointXYZI().

◆ PointXYZI() [3/3]

pcl::PointXYZI::PointXYZI ( float _x,
float _y,
float _z,
float _intensity = 0.f )
inlineconstexpr

Definition at line 462 of file point_types.hpp.

◆ operator<<

std::ostream & operator<< ( std::ostream & os,
const PointXYZI & p )
friend

References PointXYZI().


The documentation for this struct was generated from the following file: