39 #ifndef PCL_IMPL_POINT_TYPES_HPP_ 40 #define PCL_IMPL_POINT_TYPES_HPP_ 43 # pragma GCC system_header 50 #define PCL_POINT_TYPES \ 60 (pcl::InterestPoint) \ 64 (pcl::PointXYZRGBNormal) \ 65 (pcl::PointXYZINormal) \ 66 (pcl::PointXYZLNormal) \ 67 (pcl::PointWithRange) \ 68 (pcl::PointWithViewpoint) \ 69 (pcl::MomentInvariants) \ 70 (pcl::PrincipalRadiiRSD) \ 72 (pcl::PrincipalCurvatures) \ 73 (pcl::PFHSignature125) \ 74 (pcl::PFHRGBSignature250) \ 76 (pcl::CPPFSignature) \ 77 (pcl::PPFRGBSignature) \ 78 (pcl::NormalBasedSignature12) \ 79 (pcl::FPFHSignature33) \ 80 (pcl::VFHSignature308) \ 81 (pcl::GRSDSignature21) \ 82 (pcl::ESFSignature640) \ 83 (pcl::BRISKSignature512) \ 85 (pcl::IntensityGradient) \ 86 (pcl::PointWithScale) \ 88 (pcl::ShapeContext1980) \ 89 (pcl::UniqueShapeContext1960) \ 93 (pcl::ReferenceFrame) \ 97 #define PCL_RGB_POINT_TYPES \ 100 (pcl::PointXYZRGBL) \ 101 (pcl::PointXYZRGBNormal) \ 105 #define PCL_XYZ_POINT_TYPES \ 109 (pcl::PointXYZRGBA) \ 111 (pcl::PointXYZRGBL) \ 113 (pcl::InterestPoint) \ 115 (pcl::PointXYZRGBNormal) \ 116 (pcl::PointXYZINormal) \ 117 (pcl::PointXYZLNormal) \ 118 (pcl::PointWithRange) \ 119 (pcl::PointWithViewpoint) \ 120 (pcl::PointWithScale) \ 125 #define PCL_XYZL_POINT_TYPES \ 127 (pcl::PointXYZRGBL) \ 128 (pcl::PointXYZLNormal) 131 #define PCL_NORMAL_POINT_TYPES \ 134 (pcl::PointXYZRGBNormal) \ 135 (pcl::PointXYZINormal) \ 136 (pcl::PointXYZLNormal) \ 140 #define PCL_FEATURE_POINT_TYPES \ 141 (pcl::PFHSignature125) \ 142 (pcl::PFHRGBSignature250) \ 143 (pcl::PPFSignature) \ 144 (pcl::CPPFSignature) \ 145 (pcl::PPFRGBSignature) \ 146 (pcl::NormalBasedSignature12) \ 147 (pcl::FPFHSignature33) \ 148 (pcl::VFHSignature308) \ 149 (pcl::GRSDSignature21) \ 150 (pcl::ESFSignature640) \ 151 (pcl::BRISKSignature512) \ 159 typedef Eigen::Map<Eigen::Array4f, Eigen::Aligned>
Array4fMap;
173 #define PCL_ADD_UNION_POINT4D \ 174 union EIGEN_ALIGN16 { \ 183 #define PCL_ADD_EIGEN_MAPS_POINT4D \ 184 inline pcl::Vector3fMap getVector3fMap () { return (pcl::Vector3fMap (data)); } \ 185 inline pcl::Vector3fMapConst getVector3fMap () const { return (pcl::Vector3fMapConst (data)); } \ 186 inline pcl::Vector4fMap getVector4fMap () { return (pcl::Vector4fMap (data)); } \ 187 inline pcl::Vector4fMapConst getVector4fMap () const { return (pcl::Vector4fMapConst (data)); } \ 188 inline pcl::Array3fMap getArray3fMap () { return (pcl::Array3fMap (data)); } \ 189 inline pcl::Array3fMapConst getArray3fMap () const { return (pcl::Array3fMapConst (data)); } \ 190 inline pcl::Array4fMap getArray4fMap () { return (pcl::Array4fMap (data)); } \ 191 inline pcl::Array4fMapConst getArray4fMap () const { return (pcl::Array4fMapConst (data)); } 193 #define PCL_ADD_POINT4D \ 194 PCL_ADD_UNION_POINT4D \ 195 PCL_ADD_EIGEN_MAPS_POINT4D 197 #define PCL_ADD_UNION_NORMAL4D \ 198 union EIGEN_ALIGN16 { \ 208 #define PCL_ADD_EIGEN_MAPS_NORMAL4D \ 209 inline pcl::Vector3fMap getNormalVector3fMap () { return (pcl::Vector3fMap (data_n)); } \ 210 inline pcl::Vector3fMapConst getNormalVector3fMap () const { return (pcl::Vector3fMapConst (data_n)); } \ 211 inline pcl::Vector4fMap getNormalVector4fMap () { return (pcl::Vector4fMap (data_n)); } \ 212 inline pcl::Vector4fMapConst getNormalVector4fMap () const { return (pcl::Vector4fMapConst (data_n)); } 214 #define PCL_ADD_NORMAL4D \ 215 PCL_ADD_UNION_NORMAL4D \ 216 PCL_ADD_EIGEN_MAPS_NORMAL4D 218 #define PCL_ADD_UNION_RGB \ 235 #define PCL_ADD_EIGEN_MAPS_RGB \ 236 inline Eigen::Vector3i getRGBVector3i () { return (Eigen::Vector3i (r, g, b)); } \ 237 inline const Eigen::Vector3i getRGBVector3i () const { return (Eigen::Vector3i (r, g, b)); } \ 238 inline Eigen::Vector4i getRGBVector4i () { return (Eigen::Vector4i (r, g, b, a)); } \ 239 inline const Eigen::Vector4i getRGBVector4i () const { return (Eigen::Vector4i (r, g, b, a)); } \ 240 inline Eigen::Vector4i getRGBAVector4i () { return (Eigen::Vector4i (r, g, b, a)); } \ 241 inline const Eigen::Vector4i getRGBAVector4i () const { return (Eigen::Vector4i (r, g, b, a)); } \ 242 inline pcl::Vector3cMap getBGRVector3cMap () { return (pcl::Vector3cMap (reinterpret_cast<uint8_t*> (&rgba))); } \ 243 inline pcl::Vector3cMapConst getBGRVector3cMap () const { return (pcl::Vector3cMapConst (reinterpret_cast<const uint8_t*> (&rgba))); } \ 244 inline pcl::Vector4cMap getBGRAVector4cMap () { return (pcl::Vector4cMap (reinterpret_cast<uint8_t*> (&rgba))); } \ 245 inline pcl::Vector4cMapConst getBGRAVector4cMap () const { return (pcl::Vector4cMapConst (reinterpret_cast<const uint8_t*> (&rgba))); } 247 #define PCL_ADD_RGB \ 249 PCL_ADD_EIGEN_MAPS_RGB 251 #define PCL_ADD_INTENSITY \ 257 #define PCL_ADD_INTENSITY_8U \ 263 #define PCL_ADD_INTENSITY_32U \ 266 uint32_t intensity; \ 274 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
285 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
296 x = _x; y = _y; z = _z;
301 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
313 PCL_EXPORTS std::ostream&
operator << (std::ostream& os,
const RGB& p);
345 friend std::ostream&
operator << (std::ostream& os,
const RGB& p);
363 intensity = p.intensity;
389 intensity = p.intensity;
397 #if defined(_LIBCPP_VERSION) && _LIBCPP_VERSION <= 1101 398 operator unsigned char()
const 421 intensity = p.intensity;
446 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
454 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
468 intensity = _intensity;
478 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
486 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
514 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
542 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
562 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
570 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
609 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
630 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
639 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
652 inline PointXYZRGBL (uint8_t _r, uint8_t _g, uint8_t _b, uint32_t _label)
664 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
681 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
689 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
690 h = p.
h; s = p.
s; v = p.
v;
697 h = s = v = data_c[3] = 0;
703 h = _h; v = _v; s = _s;
708 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
753 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
769 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
780 normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z;
787 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
791 inline Normal (
float n_x,
float n_y,
float n_z)
793 normal_x = n_x; normal_y = n_y; normal_z = n_z;
799 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
806 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
809 PCL_EXPORTS std::ostream&
operator << (std::ostream& os,
const Axis& p);
817 normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z;
823 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
826 inline Axis (
float n_x,
float n_y,
float n_z)
828 normal_x = n_x; normal_y = n_y; normal_z = n_z;
833 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
849 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
860 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
861 normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
869 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
890 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
927 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
928 normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
938 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
958 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
969 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
970 normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
979 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
1001 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1012 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
1013 normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
1022 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
1044 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1055 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
1083 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1094 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
1099 float _vp_x = 0.0f,
float _vp_y = 0.0f,
float _vp_z = 0.0f)
1101 x = _x; y = _y; z = _z;
1103 vp_x = _vp_x; vp_y = _vp_y; vp_z = _vp_z;
1139 #if defined(_LIBCPP_VERSION) && _LIBCPP_VERSION <= 1101 1140 operator unsigned char()
const 1142 return boundary_point;
1157 float principal_curvature[3];
1177 float histogram[125];
1189 float histogram[250];
1213 float f1, f2, f3, f4, f5, f6, f7, f8,
f9, f10;
1250 float descriptor[1980];
1263 float descriptor[1960];
1276 float descriptor[352];
1290 float descriptor[1344];
1315 inline const Eigen::Map<const Eigen::Vector3f>
getXAxisVector3fMap ()
const {
return (Eigen::Vector3f::Map (x_axis)); }
1317 inline const Eigen::Map<const Eigen::Vector3f>
getYAxisVector3fMap ()
const {
return (Eigen::Vector3f::Map (y_axis)); }
1319 inline const Eigen::Map<const Eigen::Vector3f>
getZAxisVector3fMap ()
const {
return (Eigen::Vector3f::Map (z_axis)); }
1320 inline Eigen::Map<Eigen::Matrix3f>
getMatrix3fMap () {
return (Eigen::Matrix3f::Map (rf)); }
1321 inline const Eigen::Map<const Eigen::Matrix3f>
getMatrix3fMap ()
const {
return (Eigen::Matrix3f::Map (rf)); }
1323 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1331 for (
int d = 0; d < 9; ++d)
1337 for (
int d = 0; d < 3; ++d)
1338 x_axis[d] = y_axis[d] = z_axis[d] = 0;
1342 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1352 float histogram[33];
1364 float histogram[308];
1376 float histogram[21];
1390 unsigned char descriptor[64];
1402 float histogram[640];
1414 float histogram[16];
1426 float x, y,
z, roll, pitch, yaw;
1427 float descriptor[36];
1495 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1506 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
1535 inline PointWithScale (
float _x,
float _y,
float _z,
float _scale,
float _angle,
float _response,
int _octave)
1542 response = _response;
1567 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1578 x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
1589 normal_x = normal_y = normal_z = data_n[3] = 0.0f;
1591 radius = confidence = curvature = 0.0f;
1603 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1614 x = p.x; y = p.y; x = p.z; data[3] = 1.0f;
1622 x = y = z = 0.0f; data[3] = 1.0f;
1624 intensity_variance = height_variance = 0.0f;
1630 template <
int N> std::ostream&
1631 operator << (std::ostream& os, const Histogram<N>& p)
1633 for (
int i = 0; i < N; ++i)
1634 os << (i == 0 ?
"(" :
"") << p.histogram[i] << (i < N-1 ?
", " :
")");
1640 #include <pcl/common/point_tests.h>
PointXYZI(float _intensity)
A point structure representing normal coordinates and the surface curvature estimate.
const Eigen::Map< const Eigen::Array4f, Eigen::Aligned > Array4fMapConst
A point structure representing the grayscale intensity in single-channel images.
A point structure representing a Shape Context.
Eigen::Map< Eigen::Vector3f > getXAxisVector3fMap()
A point structure representing a description of whether a point is lying on a surface boundary or not...
A point structure representing Euclidean xyz coordinates, a label, together with normal coordinates a...
static int descriptorSize()
A point structure representing Euclidean xyz coordinates, padded with an extra range float...
PointDEM(const _PointDEM &p)
struct pcl::PointXYZIEdge EIGEN_ALIGN16
static int descriptorSize()
float scale
Diameter of the meaningfull keypoint neighborhood.
A point structure representing the Normal Based Signature for a feature matrix of 4-by-3...
A point structure representing a Unique Shape Context.
PointWithScale(float _x, float _y, float _z, float _scale)
Eigen::Map< Eigen::Vector3f > getZAxisVector3fMap()
A structure representing the Local Reference Frame of a point.
const Eigen::Map< const Vector4c, Eigen::Aligned > Vector4cMapConst
float angle
Computed orientation of the keypoint (-1 if not applicable).
Eigen::Map< Eigen::Vector3f > Vector3fMap
PointXYZRGBNormal(const _PointXYZRGBNormal &p)
static int descriptorSize()
const Eigen::Map< const Eigen::Vector3f > getZAxisVector3fMap() const
A point structure representing Digital Elevation Map.
static int descriptorSize()
A point structure representing the Binary Robust Invariant Scalable Keypoints (BRISK).
PointXYZ(float _x, float _y, float _z)
PointXYZRGBA(const _PointXYZRGBA &p)
float response
The response by which the most strong keypoints have been selected.
static int descriptorSize()
PointWithScale(float _x, float _y, float _z, float _scale, float _angle, float _response, int _octave)
PointXYZRGB(uint8_t _r, uint8_t _g, uint8_t _b)
A point structure representing an Axis using its normal coordinates.
const Eigen::Map< const Eigen::Vector4f, Eigen::Aligned > Vector4fMapConst
A point structure representing Euclidean xyz coordinates, and the RGBA color.
Intensity8u(const _Intensity8u &p)
A point structure representing the grayscale intensity in single-channel images.
std::ostream & operator<<(std::ostream &os, const BivariatePolynomialT< real > &p)
A point structure representing the Fast Point Feature Histogram (FPFH).
A 2D point structure representing Euclidean xy coordinates.
Eigen::Map< Vector3c > Vector3cMap
PointXYZ(const _PointXYZ &p)
A structure representing RGB color information.
A point structure representing an N-D histogram.
A 2D point structure representing pixel image coordinates.
PointXYZRGBL(uint8_t _r, uint8_t _g, uint8_t _b, uint32_t _label)
A point structure representing the GFPFH descriptor with 16 bins.
const Eigen::Map< const Eigen::Vector3f > getXAxisVector3fMap() const
A point structure representing the Point Feature Histogram with colors (PFHRGB).
float principal_curvature_z
A point structure representing Euclidean xyz coordinates, and the intensity value.
static int descriptorSize()
float principal_curvature_x
float principal_curvature_y
PointXYZRGBL(const _PointXYZRGBL &p)
const Eigen::Map< const Eigen::Vector3f > Vector3fMapConst
A point structure representing Euclidean xyz coordinates.
A point structure representing Euclidean xyz coordinates, intensity, together with normal coordinates...
static int descriptorSize()
A point structure representing an interest point with Euclidean xyz coordinates, and an interest valu...
PointXYZINormal(const _PointXYZINormal &p)
A point structure representing the three moment invariants.
Eigen::Map< Eigen::Array4f, Eigen::Aligned > Array4fMap
PointXYZLNormal(const _PointXYZLNormal &p)
Eigen::Map< Eigen::Vector3f > getYAxisVector3fMap()
PointXYZI(const _PointXYZI &p)
const Eigen::Map< const Eigen::Matrix3f > getMatrix3fMap() const
A point structure representing the grayscale intensity in single-channel images.
PointXYZHSV(const _PointXYZHSV &p)
Normal(float n_x, float n_y, float n_z)
A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape onl...
static int descriptorSize()
Axis(float n_x, float n_y, float n_z)
PointSurfel(const _PointSurfel &p)
static int descriptorSize()
int octave
octave (pyramid layer) from which the keypoint has been extracted.
A structure to store if a point in a range image lies on a border between an obstacle and the backgro...
ReferenceFrame(const _ReferenceFrame &p)
A point structure representing Euclidean xyz coordinates, together with normal coordinates and the su...
Intensity32u(const _Intensity32u &p)
A point structure for storing the Point Pair Feature (CPPF) values.
Eigen::Matrix< uint8_t, 4, 1 > Vector4c
A point structure representing Euclidean xyz coordinates together with the viewpoint from which it wa...
A point structure representing the intensity gradient of an XYZI point cloud.
Eigen::Map< Eigen::Array3f > Array3fMap
const Eigen::Map< const Vector3c > Vector3cMapConst
Eigen::Map< Eigen::Vector4f, Eigen::Aligned > Vector4fMap
Eigen::Map< Vector4c, Eigen::Aligned > Vector4cMap
A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape+col...
static int descriptorSize()
PointXYZRGB(const _PointXYZRGB &p)
A point structure representing the Viewpoint Feature Histogram (VFH).
A point structure representing a 3-D position and scale.
A point structure representing the minimum and maximum surface radii (in meters) computed using RSD...
A point structure representing the Narf descriptor.
A point structure representing Euclidean xyz coordinates, and the RGB color.
A point structure representing the principal curvatures and their magnitudes.
PointWithRange(const _PointWithRange &p)
PointWithScale(const _PointWithScale &p)
A point structure representing the Point Feature Histogram (PFH).
PointWithViewpoint(const _PointWithViewpoint &p)
A point structure representing the Ensemble of Shape Functions (ESF).
static int descriptorSize()
Intensity(const _Intensity &p)
static int descriptorSize()
PointXYZHSV(float _h, float _v, float _s)
A point structure representing the Global Radius-based Surface Descriptor (GRSD). ...
Eigen::Matrix< uint8_t, 3, 1 > Vector3c
const Eigen::Map< const Eigen::Array3f > Array3fMapConst
PointXYZL(const _PointXYZL &p)
A surfel, that is, a point structure representing Euclidean xyz coordinates, together with normal coo...
PointNormal(const _PointNormal &p)
std::bitset< 32 > BorderTraits
Data type to store extended information about a transition from foreground to backgroundSpecification...
PointWithViewpoint(float _x=0.0f, float _y=0.0f, float _z=0.0f, float _vp_x=0.0f, float _vp_y=0.0f, float _vp_z=0.0f)
static int descriptorSize()
A point structure representing Euclidean xyz coordinates, and the RGB color, together with normal coo...
A point structure for storing the Point Pair Feature (PPF) values.
static int descriptorSize()
const Eigen::Map< const Eigen::Vector3f > getYAxisVector3fMap() const
Eigen::Map< Eigen::Matrix3f > getMatrix3fMap()
A point structure for storing the Point Pair Color Feature (PPFRGB) values.