point_types.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #ifndef PCL_IMPL_POINT_TYPES_HPP_
00040 #define PCL_IMPL_POINT_TYPES_HPP_
00041 
00042 #if defined __GNUC__
00043 #  pragma GCC system_header
00044 #endif
00045 
00046 #include <Eigen/Core>
00047 #include <ostream>
00048 
00049 // Define all PCL point types
00050 #define PCL_POINT_TYPES         \
00051   (pcl::PointXYZ)               \
00052   (pcl::PointXYZI)              \
00053   (pcl::PointXYZL)              \
00054   (pcl::Label)                  \
00055   (pcl::PointXYZRGBA)           \
00056   (pcl::PointXYZRGB)            \
00057   (pcl::PointXYZRGBL)           \
00058   (pcl::PointXYZHSV)            \
00059   (pcl::PointXY)                \
00060   (pcl::InterestPoint)          \
00061   (pcl::Axis)                   \
00062   (pcl::Normal)                 \
00063   (pcl::PointNormal)            \
00064   (pcl::PointXYZRGBNormal)      \
00065   (pcl::PointXYZINormal)        \
00066   (pcl::PointWithRange)         \
00067   (pcl::PointWithViewpoint)     \
00068   (pcl::MomentInvariants)       \
00069   (pcl::PrincipalRadiiRSD)      \
00070   (pcl::Boundary)               \
00071   (pcl::PrincipalCurvatures)    \
00072   (pcl::PFHSignature125)        \
00073   (pcl::PFHRGBSignature250)     \
00074   (pcl::PPFSignature)           \
00075   (pcl::PPFRGBSignature)        \
00076   (pcl::NormalBasedSignature12) \
00077   (pcl::FPFHSignature33)        \
00078   (pcl::VFHSignature308)        \
00079   (pcl::ESFSignature640)        \
00080   (pcl::Narf36)                 \
00081   (pcl::IntensityGradient)      \
00082   (pcl::PointWithScale)         \
00083   (pcl::PointSurfel)            \
00084   (pcl::ShapeContext1980)       \
00085   (pcl::SHOT352)                \
00086   (pcl::SHOT1344)               \
00087   (pcl::PointUV)                \
00088   (pcl::ReferenceFrame)
00089 
00090 // Define all point types that include RGB data
00091 #define PCL_RGB_POINT_TYPES     \
00092   (pcl::PointXYZRGBA)           \
00093   (pcl::PointXYZRGB)            \
00094   (pcl::PointXYZRGBL)           \
00095   (pcl::PointXYZRGBNormal)      \
00096   (pcl::PointSurfel)            \
00097 
00098 // Define all point types that include XYZ data
00099 #define PCL_XYZ_POINT_TYPES   \
00100   (pcl::PointXYZ)             \
00101   (pcl::PointXYZI)            \
00102   (pcl::PointXYZL)            \
00103   (pcl::PointXYZRGBA)         \
00104   (pcl::PointXYZRGB)          \
00105   (pcl::PointXYZRGBL)         \
00106   (pcl::PointXYZHSV)          \
00107   (pcl::InterestPoint)        \
00108   (pcl::PointNormal)          \
00109   (pcl::PointXYZRGBNormal)    \
00110   (pcl::PointXYZINormal)      \
00111   (pcl::PointWithRange)       \
00112   (pcl::PointWithViewpoint)   \
00113   (pcl::PointWithScale)       \
00114   (pcl::PointSurfel)
00115 
00116 // Define all point types with XYZ and label
00117 #define PCL_XYZL_POINT_TYPES  \
00118   (pcl::PointXYZL)            \
00119   (pcl::PointXYZRGBL)
00120 
00121 // Define all point types that include normal[3] data
00122 #define PCL_NORMAL_POINT_TYPES  \
00123   (pcl::Normal)                 \
00124   (pcl::PointNormal)            \
00125   (pcl::PointXYZRGBNormal)      \
00126   (pcl::PointXYZINormal)        \
00127   (pcl::PointSurfel)
00128 
00129 // Define all point types that represent features
00130 #define PCL_FEATURE_POINT_TYPES \
00131   (pcl::PFHSignature125)        \
00132   (pcl::PFHRGBSignature250)     \
00133   (pcl::PPFSignature)           \
00134   (pcl::PPFRGBSignature)        \
00135   (pcl::NormalBasedSignature12) \
00136   (pcl::FPFHSignature33)        \
00137   (pcl::VFHSignature308)        \
00138   (pcl::ESFSignature640)        \
00139   (pcl::Narf36)
00140 
00141 namespace pcl
00142 {
00143 
00144 #define PCL_ADD_POINT4D \
00145   union EIGEN_ALIGN16 { \
00146     float data[4]; \
00147     struct { \
00148       float x; \
00149       float y; \
00150       float z; \
00151     }; \
00152   }; \
00153   inline Eigen::Map<Eigen::Vector3f> getVector3fMap () { return (Eigen::Vector3f::Map (data)); } \
00154   inline const Eigen::Map<const Eigen::Vector3f> getVector3fMap () const { return (Eigen::Vector3f::Map (data)); } \
00155   inline Eigen::Map<Eigen::Vector4f, Eigen::Aligned> getVector4fMap () { return (Eigen::Vector4f::MapAligned (data)); } \
00156   inline const Eigen::Map<const Eigen::Vector4f, Eigen::Aligned> getVector4fMap () const { return (Eigen::Vector4f::MapAligned (data)); } \
00157   inline Eigen::Map<Eigen::Array3f> getArray3fMap () { return (Eigen::Array3f::Map (data)); } \
00158   inline const Eigen::Map<const Eigen::Array3f> getArray3fMap () const { return (Eigen::Array3f::Map (data)); } \
00159   inline Eigen::Map<Eigen::Array4f, Eigen::Aligned> getArray4fMap () { return (Eigen::Array4f::MapAligned (data)); } \
00160   inline const Eigen::Map<const Eigen::Array4f, Eigen::Aligned> getArray4fMap () const { return (Eigen::Array4f::MapAligned (data)); }
00161 
00162 #define PCL_ADD_NORMAL4D \
00163   union EIGEN_ALIGN16 { \
00164     float data_n[4]; \
00165     float normal[3]; \
00166     struct { \
00167       float normal_x; \
00168       float normal_y; \
00169       float normal_z; \
00170     }; \
00171   }; \
00172   inline Eigen::Map<Eigen::Vector3f> getNormalVector3fMap () { return (Eigen::Vector3f::Map (data_n)); } \
00173   inline const Eigen::Map<const Eigen::Vector3f> getNormalVector3fMap () const { return (Eigen::Vector3f::Map (data_n)); } \
00174   inline Eigen::Map<Eigen::Vector4f, Eigen::Aligned> getNormalVector4fMap () { return (Eigen::Vector4f::MapAligned (data_n)); } \
00175   inline const Eigen::Map<const Eigen::Vector4f, Eigen::Aligned> getNormalVector4fMap () const { return (Eigen::Vector4f::MapAligned (data_n)); }
00176 
00177 #define PCL_ADD_RGB \
00178   union \
00179   { \
00180     union \
00181     { \
00182       struct \
00183       { \
00184         uint8_t b; \
00185         uint8_t g; \
00186         uint8_t r; \
00187         uint8_t a; \
00188       }; \
00189       float rgb; \
00190     }; \
00191     uint32_t rgba; \
00192   };
00193 
00194 #define PCL_ADD_INTENSITY \
00195     struct \
00196     { \
00197       float intensity; \
00198     }; \
00199 
00200 #define PCL_ADD_INTENSITY_8U \
00201     struct \
00202     { \
00203       uint8_t intensity; \
00204     }; \
00205 
00206 #define PCL_ADD_INTENSITY_32U \
00207     struct \
00208     { \
00209         uint32_t intensity; \
00210     }; \
00211 
00212   typedef Eigen::Map<Eigen::Array3f> Array3fMap;
00213   typedef const Eigen::Map<const Eigen::Array3f> Array3fMapConst;
00214   typedef Eigen::Map<Eigen::Array4f, Eigen::Aligned> Array4fMap;
00215   typedef const Eigen::Map<const Eigen::Array4f, Eigen::Aligned> Array4fMapConst;
00216   typedef Eigen::Map<Eigen::Vector3f> Vector3fMap;
00217   typedef const Eigen::Map<const Eigen::Vector3f> Vector3fMapConst;
00218   typedef Eigen::Map<Eigen::Vector4f, Eigen::Aligned> Vector4fMap;
00219   typedef const Eigen::Map<const Eigen::Vector4f, Eigen::Aligned> Vector4fMapConst;
00220 
00221 
00222   struct _PointXYZ
00223   {
00224     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00225 
00226     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00227   };
00228 
00229   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZ& p);
00233   struct EIGEN_ALIGN16 PointXYZ : public _PointXYZ
00234   {
00235     inline PointXYZ (const _PointXYZ &p)
00236     {
00237       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00238     }
00239 
00240     inline PointXYZ ()
00241     {
00242       x = y = z = 0.0f;
00243       data[3] = 1.0f;
00244     }
00245 
00246     inline PointXYZ (float _x, float _y, float _z)
00247     {
00248       x = _x; y = _y; z = _z;
00249       data[3] = 1.0f;
00250     }
00251 
00252     friend std::ostream& operator << (std::ostream& os, const PointXYZ& p);
00253     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00254   };
00255 
00256 
00257 #ifdef RGB
00258 #undef RGB
00259 #endif
00260   struct _RGB
00261   {
00262     PCL_ADD_RGB;
00263   };
00264 
00265   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const RGB& p);
00285   struct RGB: public _RGB
00286   {
00287     inline RGB (const _RGB &p)
00288     {
00289       rgba = p.rgba;
00290     }
00291 
00292     inline RGB ()
00293     {
00294       r = g = b = a = 0;
00295     }
00296   
00297     friend std::ostream& operator << (std::ostream& os, const RGB& p);
00298   };
00299   
00300 
00301   struct _Intensity
00302   {
00303     PCL_ADD_INTENSITY;
00304   };
00305 
00306   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity& p);
00311   struct Intensity: public _Intensity
00312   {
00313     inline Intensity (const _Intensity &p)
00314     {
00315       intensity = p.intensity;
00316     }
00317 
00318     inline Intensity ()
00319     {
00320       intensity = 0.0f;
00321     }
00322   
00323     friend std::ostream& operator << (std::ostream& os, const Intensity& p);
00324   };
00325   
00326 
00327   struct _Intensity8u
00328   {
00329     PCL_ADD_INTENSITY_8U;
00330   };
00331 
00332   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity8u& p);
00337   struct Intensity8u: public _Intensity8u
00338   {
00339     inline Intensity8u (const _Intensity8u &p)
00340     {
00341       intensity = p.intensity;
00342     }
00343 
00344     inline Intensity8u ()
00345     {
00346       intensity = 0;
00347     }
00348   
00349     friend std::ostream& operator << (std::ostream& os, const Intensity8u& p);
00350   };
00351 
00352   struct _Intensity32u
00353   {
00354     PCL_ADD_INTENSITY_32U;
00355   };
00356 
00357   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity32u& p);
00362   struct Intensity32u: public _Intensity32u
00363   {
00364     inline Intensity32u (const _Intensity32u &p)
00365     {
00366       intensity = p.intensity;
00367     }
00368 
00369     inline Intensity32u ()
00370     {
00371       intensity = 0;
00372     }
00373 
00374     friend std::ostream& operator << (std::ostream& os, const Intensity32u& p);
00375   };
00376 
00380   struct EIGEN_ALIGN16 _PointXYZI
00381   {
00382     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00383     union
00384     {
00385       struct
00386       {
00387         float intensity;
00388       };
00389       float data_c[4];
00390     };
00391     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00392   };
00393 
00394   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZI& p);
00395   struct PointXYZI : public _PointXYZI
00396   {
00397     inline PointXYZI (const _PointXYZI &p)
00398     {
00399       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00400       intensity = p.intensity;
00401     }
00402 
00403     inline PointXYZI ()
00404     {
00405       x = y = z = 0.0f;
00406       data[3] = 1.0f;
00407       intensity = 0.0f;
00408     }
00409     inline PointXYZI (float _intensity)
00410     {
00411       x = y = z = 0.0f;
00412       data[3] = 1.0f;
00413       intensity = _intensity;
00414     }
00415     friend std::ostream& operator << (std::ostream& os, const PointXYZI& p);
00416   };
00417   
00418 
00419   struct EIGEN_ALIGN16 _PointXYZL
00420   {
00421     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00422     uint32_t label;
00423     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00424   };
00425 
00426   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZL& p);
00427   struct PointXYZL : public _PointXYZL
00428   {
00429     inline PointXYZL (const _PointXYZL &p)
00430     {
00431       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00432       label = p.label;
00433     }
00434 
00435     inline PointXYZL ()
00436     {
00437       x = y = z = 0.0f;
00438       data[3] = 1.0f;
00439       label = 0;
00440     }
00441   
00442     friend std::ostream& operator << (std::ostream& os, const PointXYZL& p);
00443   };
00444 
00445 
00446   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Label& p);
00447   struct Label
00448   {
00449     uint32_t label;
00450   
00451     friend std::ostream& operator << (std::ostream& os, const Label& p);
00452   };
00453 
00454 
00455   struct EIGEN_ALIGN16 _PointXYZRGBA
00456   {
00457     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00458     PCL_ADD_RGB;
00459     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00460   };
00461 
00462   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGBA& p);
00483   struct EIGEN_ALIGN16 PointXYZRGBA : public _PointXYZRGBA
00484   {
00485     inline PointXYZRGBA (const _PointXYZRGBA &p)
00486     {
00487       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00488       rgba = p.rgba;
00489     }
00490 
00491     inline PointXYZRGBA ()
00492     {
00493       x = y = z = 0.0f;
00494       data[3] = 1.0f;
00495       r = g = b = a = 0;
00496     }
00497     inline Eigen::Vector3i getRGBVector3i ()
00498     {
00499       return (Eigen::Vector3i (r, g, b));
00500     }
00501     inline const Eigen::Vector3i getRGBVector3i () const { return (Eigen::Vector3i (r, g, b)); }
00502     inline Eigen::Vector4i getRGBVector4i ()
00503     {
00504       return (Eigen::Vector4i (r, g, b, a));
00505     }
00506     inline const Eigen::Vector4i getRGBVector4i () const { return (Eigen::Vector4i (r, g, b, a)); }
00507   
00508     friend std::ostream& operator << (std::ostream& os, const PointXYZRGBA& p);
00509   };
00510 
00511 
00512   struct EIGEN_ALIGN16 _PointXYZRGB
00513   {
00514     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00515     PCL_ADD_RGB;
00516     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00517   };
00518 
00519   struct EIGEN_ALIGN16 _PointXYZRGBL
00520   {
00521     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00522     PCL_ADD_RGB;
00523     uint32_t label;
00524     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00525   };
00526 
00527   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGB& p);
00559   struct EIGEN_ALIGN16 PointXYZRGB : public _PointXYZRGB
00560   {
00561     inline PointXYZRGB (const _PointXYZRGB &p)
00562     {
00563       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00564       rgb = p.rgb;
00565     }
00566 
00567     inline PointXYZRGB ()
00568     {
00569       x = y = z = 0.0f;
00570       data[3] = 1.0f;
00571       r = g = b = a = 0;
00572     }
00573     inline PointXYZRGB (uint8_t _r, uint8_t _g, uint8_t _b)
00574     {
00575       x = y = z = 0.0f;
00576       data[3] = 1.0f;
00577       r = _r;
00578       g = _g;
00579       b = _b;
00580       a = 0;
00581     }
00582 
00583     inline Eigen::Vector3i getRGBVector3i ()
00584     {
00585       return (Eigen::Vector3i (r, g, b));
00586     }
00587     inline const Eigen::Vector3i getRGBVector3i () const { return (Eigen::Vector3i (r, g, b)); }
00588     inline Eigen::Vector4i getRGBVector4i ()
00589     {
00590       return (Eigen::Vector4i (r, g, b, a));
00591     }
00592     inline const Eigen::Vector4i getRGBVector4i () const { return (Eigen::Vector4i (r, g, b, a)); }
00593 
00594   
00595     friend std::ostream& operator << (std::ostream& os, const PointXYZRGB& p);
00596     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00597   };
00598 
00599 
00600   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGBL& p);
00601   struct EIGEN_ALIGN16 PointXYZRGBL : public _PointXYZRGBL
00602   {
00603     inline PointXYZRGBL (const _PointXYZRGBL &p)
00604     {
00605       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00606       rgba = p.rgba;
00607       label = p.label;
00608     }
00609 
00610     inline PointXYZRGBL ()
00611     {
00612       x = y = z = 0.0f;
00613       data[3] = 1.0f;
00614       r = g = b = 0;
00615       a = 0;
00616       label = 255;
00617     }
00618     inline PointXYZRGBL (uint8_t _r, uint8_t _g, uint8_t _b, uint32_t _label)
00619     {
00620       x = y = z = 0.0f;
00621       data[3] = 1.0f;
00622       r = _r;
00623       g = _g;
00624       b = _b;
00625       a = 0;
00626       label = _label;
00627     }
00628   
00629     friend std::ostream& operator << (std::ostream& os, const PointXYZRGBL& p);
00630     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00631   };
00632 
00633 
00634   struct _PointXYZHSV
00635   {
00636     PCL_ADD_POINT4D;    // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00637     union
00638     {
00639       struct
00640       {
00641         float h;
00642         float s;
00643         float v;
00644       };
00645       float data_c[4];
00646     };
00647     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00648   } EIGEN_ALIGN16;
00649 
00650   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZHSV& p);
00651   struct EIGEN_ALIGN16 PointXYZHSV : public _PointXYZHSV
00652   {
00653     inline PointXYZHSV (const _PointXYZHSV &p)
00654     {
00655       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00656       h = p.h; s = p.s; v = p.v;
00657     }
00658 
00659     inline PointXYZHSV ()
00660     {
00661       x = y = z = 0.0f;
00662       data[3] = 1.0f;
00663       h = s = v = data_c[3] = 0;
00664     }
00665     inline PointXYZHSV (float _h, float _v, float _s)
00666     {
00667       x = y = z = 0.0f;
00668       data[3] = 1.0f;
00669       h = _h; v = _v; s = _s;
00670       data_c[3] = 0;
00671     }
00672   
00673     friend std::ostream& operator << (std::ostream& os, const PointXYZHSV& p);
00674     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00675   };
00676 
00677 
00678 
00679   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXY& p);
00683   struct PointXY
00684   {
00685     float x;
00686     float y;
00687   
00688     friend std::ostream& operator << (std::ostream& os, const PointXY& p);
00689   };
00690 
00691   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointUV& p);
00696   struct PointUV
00697   {
00698     float u;
00699     float v;
00700   
00701     friend std::ostream& operator << (std::ostream& os, const PointUV& p);
00702   };
00703 
00704   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const InterestPoint& p);
00708   struct EIGEN_ALIGN16 InterestPoint
00709   {
00710     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00711     union
00712     {
00713       struct
00714       {
00715         float strength;
00716       };
00717       float data_c[4];
00718     };
00719     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00720   
00721     friend std::ostream& operator << (std::ostream& os, const InterestPoint& p);
00722   };
00723 
00724   struct EIGEN_ALIGN16 _Normal
00725   {
00726     PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
00727     union
00728     {
00729       struct
00730       {
00731         float curvature;
00732       };
00733       float data_c[4];
00734     };
00735     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00736   };
00737 
00738   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Normal& p);
00742   struct Normal : public _Normal
00743   {
00744     inline Normal (const _Normal &p)
00745     {
00746       normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z;
00747       data_n[3] = 0.0f;
00748       curvature = p.curvature;
00749     }
00750 
00751     inline Normal ()
00752     {
00753       normal_x = normal_y = normal_z = data_n[3] = 0.0f;
00754       curvature = 0;
00755     }
00756 
00757     inline Normal (float n_x, float n_y, float n_z)
00758     {
00759       normal_x = n_x; normal_y = n_y; normal_z = n_z;
00760       curvature = 0;
00761       data_n[3] = 0.0f;
00762     }
00763 
00764     friend std::ostream& operator << (std::ostream& os, const Normal& p);
00765     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00766   };
00767 
00768 
00769   struct EIGEN_ALIGN16 _Axis
00770   {
00771     PCL_ADD_NORMAL4D;
00772     EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
00773   };
00774 
00775   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Axis& p);
00779   struct EIGEN_ALIGN16 Axis : public _Axis
00780   {
00781     inline Axis (const _Axis &p)
00782     {
00783       normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z;
00784       data_n[3] = 0.0f;
00785     }
00786 
00787     inline Axis ()
00788     {
00789       normal_x = normal_y = normal_z = data_n[3] = 0.0f;
00790     }
00791 
00792     inline Axis (float n_x, float n_y, float n_z)
00793     {
00794       normal_x = n_x; normal_y = n_y; normal_z = n_z;
00795       data_n[3] = 0.0f;
00796     }
00797 
00798     friend std::ostream& operator << (std::ostream& os, const Axis& p);
00799     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00800   };
00801 
00802 
00803   struct EIGEN_ALIGN16 _PointNormal
00804   {
00805     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00806     PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
00807     union
00808     {
00809       struct
00810       {
00811         float curvature;
00812       };
00813       float data_c[4];
00814     };
00815     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00816   };
00817 
00818   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointNormal& p);
00822   struct PointNormal : public _PointNormal
00823   {
00824     inline PointNormal (const _PointNormal &p)
00825     {
00826       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00827       normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
00828       curvature = p.curvature;
00829     }
00830 
00831     inline PointNormal ()
00832     {
00833       x = y = z = 0.0f;
00834       data[3] = 1.0f;
00835       normal_x = normal_y = normal_z = data_n[3] = 0.0f;
00836     }
00837   
00838     friend std::ostream& operator << (std::ostream& os, const PointNormal& p);
00839   };
00840 
00841 
00842   struct EIGEN_ALIGN16 _PointXYZRGBNormal
00843   {
00844     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00845     PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
00846     union
00847     {
00848       struct
00849       {
00850         // RGB union
00851         union
00852         {
00853           struct
00854           {
00855             uint8_t b;
00856             uint8_t g;
00857             uint8_t r;
00858             uint8_t a;
00859           };
00860           float rgb;
00861           uint32_t rgba;
00862         };
00863         float curvature;
00864       };
00865       float data_c[4];
00866     };
00867     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00868   };
00869 
00870   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGBNormal& p);
00900   struct PointXYZRGBNormal : public _PointXYZRGBNormal
00901   {
00902     inline PointXYZRGBNormal (const _PointXYZRGBNormal &p)
00903     {
00904       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00905       normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
00906       curvature = p.curvature;
00907       rgba = p.rgba;
00908     }
00909 
00910     inline PointXYZRGBNormal ()
00911     {
00912       x = y = z = 0.0f;
00913       data[3] = 1.0f;
00914       r = g = b = a = 0;
00915       normal_x = normal_y = normal_z = data_n[3] = 0.0f;
00916       curvature = 0;
00917     }
00918 
00919     inline Eigen::Vector3i getRGBVector3i ()
00920     {
00921       return (Eigen::Vector3i (r, g, b));
00922     }
00923     inline const Eigen::Vector3i getRGBVector3i () const { return (Eigen::Vector3i (r, g, b)); }
00924     inline Eigen::Vector4i getRGBVector4i ()
00925     {
00926       return (Eigen::Vector4i (r, g, b, a));
00927     }
00928     inline const Eigen::Vector4i getRGBVector4i () const { return (Eigen::Vector4i (r, g, b, a)); }
00929   
00930     friend std::ostream& operator << (std::ostream& os, const PointXYZRGBNormal& p);
00931   };
00932 
00933   struct EIGEN_ALIGN16 _PointXYZINormal
00934   {
00935     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00936     PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
00937     union
00938     {
00939       struct
00940       {
00941         float intensity;
00942         float curvature;
00943       };
00944       float data_c[4];
00945     };
00946     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00947   };
00948   
00949   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZINormal& p);
00953   struct PointXYZINormal : public _PointXYZINormal
00954   {
00955     inline PointXYZINormal (const _PointXYZINormal &p)
00956     {
00957       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00958       normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f;
00959       curvature = p.curvature;
00960       intensity = p.intensity;
00961     }
00962 
00963     inline PointXYZINormal ()
00964     {
00965       x = y = z = 0.0f;
00966       data[3] = 1.0f;
00967       normal_x = normal_y = normal_z = data_n[3] = 0.0f;
00968       intensity = 0.0f;
00969     }
00970   
00971     friend std::ostream& operator << (std::ostream& os, const PointXYZINormal& p);
00972   };
00973 
00974 
00975   struct EIGEN_ALIGN16 _PointWithRange
00976   {
00977     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
00978     union
00979     {
00980       struct
00981       {
00982         float range;
00983       };
00984       float data_c[4];
00985     };
00986     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00987   };
00988 
00989   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointWithRange& p);
00993   struct PointWithRange : public _PointWithRange
00994   {
00995     inline PointWithRange (const _PointWithRange &p)
00996     {
00997       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
00998       range = p.range;
00999     }
01000 
01001     inline PointWithRange ()
01002     {
01003       x = y = z = 0.0f;
01004       data[3] = 1.0f;
01005       range = 0.0f;
01006     }
01007   
01008     friend std::ostream& operator << (std::ostream& os, const PointWithRange& p);
01009   };
01010 
01011 
01012   struct EIGEN_ALIGN16 _PointWithViewpoint
01013   {
01014     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
01015     union
01016     {
01017       struct
01018       {
01019         float vp_x;
01020         float vp_y;
01021         float vp_z;
01022       };
01023       float data_c[4];
01024     };
01025     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
01026   };
01027 
01028   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointWithViewpoint& p);
01032   struct EIGEN_ALIGN16 PointWithViewpoint : public _PointWithViewpoint
01033   {
01034     inline PointWithViewpoint (const _PointWithViewpoint &p)
01035     {
01036       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
01037       vp_x = p.vp_x; vp_y = p.vp_y; vp_z = p.vp_z;
01038     }
01039 
01040     inline PointWithViewpoint (float _x = 0.0f, float _y = 0.0f, float _z = 0.0f,
01041                                float _vp_x = 0.0f, float _vp_y = 0.0f, float _vp_z = 0.0f)
01042     {
01043       x = _x; y = _y; z = _z;
01044       data[3] = 1.0f;
01045       vp_x = _vp_x; vp_y = _vp_y; vp_z = _vp_z;
01046     }
01047   
01048     friend std::ostream& operator << (std::ostream& os, const PointWithViewpoint& p);
01049   };
01050 
01051   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const MomentInvariants& p);
01055   struct MomentInvariants
01056   {
01057     float j1, j2, j3;
01058   
01059     friend std::ostream& operator << (std::ostream& os, const MomentInvariants& p);
01060   };
01061 
01062   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PrincipalRadiiRSD& p);
01066   struct PrincipalRadiiRSD
01067   {
01068     float r_min, r_max;
01069   
01070     friend std::ostream& operator << (std::ostream& os, const PrincipalRadiiRSD& p);
01071   };
01072 
01073   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Boundary& p);
01077   struct Boundary
01078   {
01079     uint8_t boundary_point;
01080   
01081     friend std::ostream& operator << (std::ostream& os, const Boundary& p);
01082   };
01083 
01084   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PrincipalCurvatures& p);
01088   struct PrincipalCurvatures
01089   {
01090     union
01091     {
01092       float principal_curvature[3];
01093       struct
01094       {
01095         float principal_curvature_x;
01096         float principal_curvature_y;
01097         float principal_curvature_z;
01098       };
01099     };
01100     float pc1;
01101     float pc2;
01102   
01103     friend std::ostream& operator << (std::ostream& os, const PrincipalCurvatures& p);
01104   };
01105 
01106   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PFHSignature125& p);
01110   struct PFHSignature125
01111   {
01112     float histogram[125];
01113   
01114     friend std::ostream& operator << (std::ostream& os, const PFHSignature125& p);
01115   };
01116 
01117   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PFHRGBSignature250& p);
01121   struct PFHRGBSignature250
01122   {
01123     float histogram[250];
01124   
01125     friend std::ostream& operator << (std::ostream& os, const PFHRGBSignature250& p);
01126   };
01127 
01128   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PPFSignature& p);
01132   struct PPFSignature
01133   {
01134     float f1, f2, f3, f4;
01135     float alpha_m;
01136   
01137     friend std::ostream& operator << (std::ostream& os, const PPFSignature& p);
01138   };
01139 
01140   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PPFRGBSignature& p);
01144   struct PPFRGBSignature
01145   {
01146     float f1, f2, f3, f4;
01147     float r_ratio, g_ratio, b_ratio;
01148     float alpha_m;
01149   
01150     friend std::ostream& operator << (std::ostream& os, const PPFRGBSignature& p);
01151   };
01152 
01153   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const NormalBasedSignature12& p);
01158   struct NormalBasedSignature12
01159   {
01160     float values[12];
01161   
01162     friend std::ostream& operator << (std::ostream& os, const NormalBasedSignature12& p);
01163   };
01164 
01165   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const ShapeContext1980& p);
01169   struct ShapeContext1980
01170   {
01171     float descriptor[1980];
01172     float rf[9];
01173   
01174     friend std::ostream& operator << (std::ostream& os, const ShapeContext1980& p);
01175   };
01176 
01177 
01178   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const SHOT352& p);
01182   struct SHOT352
01183   {
01184     float descriptor[352];
01185     float rf[9];
01186   
01187     friend std::ostream& operator << (std::ostream& os, const SHOT352& p);
01188   };
01189 
01190 
01191   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const SHOT1344& p);
01195   struct SHOT1344
01196   {
01197     float descriptor[1344];
01198     float rf[9];
01199   
01200     friend std::ostream& operator << (std::ostream& os, const SHOT1344& p);
01201   };
01202 
01203 
01207   struct EIGEN_ALIGN16 _ReferenceFrame
01208   {
01209     union
01210     {
01211       float rf[9];
01212       struct
01213       {
01214         float x_axis[3];
01215         float y_axis[3];
01216         float z_axis[3];
01217       };
01218     };
01219 
01220     inline Eigen::Map<Eigen::Vector3f> getXAxisVector3fMap () { return (Eigen::Vector3f::Map (x_axis)); }
01221     inline const Eigen::Map<const Eigen::Vector3f> getXAxisVector3fMap () const { return (Eigen::Vector3f::Map (x_axis)); }
01222     inline Eigen::Map<Eigen::Vector3f> getYAxisVector3fMap () { return (Eigen::Vector3f::Map (y_axis)); }
01223     inline const Eigen::Map<const Eigen::Vector3f> getYAxisVector3fMap () const { return (Eigen::Vector3f::Map (y_axis)); }
01224     inline Eigen::Map<Eigen::Vector3f> getZAxisVector3fMap () { return (Eigen::Vector3f::Map (z_axis)); }
01225     inline const Eigen::Map<const Eigen::Vector3f> getZAxisVector3fMap () const { return (Eigen::Vector3f::Map (z_axis)); }
01226     inline Eigen::Map<Eigen::Matrix3f> getMatrix3fMap () { return (Eigen::Matrix3f::Map (rf)); }
01227     inline const Eigen::Map<const Eigen::Matrix3f> getMatrix3fMap () const { return (Eigen::Matrix3f::Map (rf)); }
01228 
01229     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
01230   };
01231 
01232   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const ReferenceFrame& p);
01233   struct EIGEN_ALIGN16 ReferenceFrame : public _ReferenceFrame
01234   {
01235     inline ReferenceFrame (const _ReferenceFrame &p)
01236     {
01237       for (int d = 0; d < 9; ++d)
01238         rf[d] = p.rf[d];
01239     }
01240 
01241     inline ReferenceFrame ()
01242     {
01243       for (int d = 0; d < 3; ++d)
01244         x_axis[d] = y_axis[d] = z_axis[d] = 0;
01245     }
01246 
01247     friend std::ostream& operator << (std::ostream& os, const ReferenceFrame& p);
01248     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
01249   };
01250 
01251 
01252   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const FPFHSignature33& p);
01256   struct FPFHSignature33
01257   {
01258     float histogram[33];
01259   
01260     friend std::ostream& operator << (std::ostream& os, const FPFHSignature33& p);
01261   };
01262 
01263   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const VFHSignature308& p);
01267   struct VFHSignature308
01268   {
01269     float histogram[308];
01270   
01271     friend std::ostream& operator << (std::ostream& os, const VFHSignature308& p);
01272   };
01273 
01274   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const ESFSignature640& p);
01278   struct ESFSignature640
01279   {
01280     float histogram[640];
01281   
01282     friend std::ostream& operator << (std::ostream& os, const ESFSignature640& p);
01283   };
01284 
01285   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const GFPFHSignature16& p);
01289   struct GFPFHSignature16
01290   {
01291     float histogram[16];
01292     static int descriptorSize() { return 16; }
01293     
01294     friend std::ostream& operator << (std::ostream& os, const GFPFHSignature16& p);
01295   };
01296 
01297   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Narf36& p);
01301   struct Narf36
01302   {
01303     float x, y, z, roll, pitch, yaw;
01304     float descriptor[36];
01305   
01306     friend std::ostream& operator << (std::ostream& os, const Narf36& p);
01307   };
01308 
01309   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const BorderDescription& p);
01313   struct BorderDescription
01314   {
01315     int x, y;
01316     BorderTraits traits;
01317     //std::vector<const BorderDescription*> neighbors;
01318   
01319     friend std::ostream& operator << (std::ostream& os, const BorderDescription& p);
01320   };
01321 
01322 
01323   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const IntensityGradient& p);
01327   struct IntensityGradient
01328   {
01329     union
01330     {
01331       float gradient[3];
01332       struct
01333       {
01334         float gradient_x;
01335         float gradient_y;
01336         float gradient_z;
01337       };
01338     };
01339   
01340     friend std::ostream& operator << (std::ostream& os, const IntensityGradient& p);
01341   };
01342 
01346   template <int N>
01347   struct Histogram
01348   {
01349     float histogram[N];
01350   };
01351 
01352   struct EIGEN_ALIGN16 _PointWithScale
01353   {
01354     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
01355 
01356     union
01357     {
01359       float scale;
01360       float size;
01361     };
01362 
01364     float angle;
01366     float response;
01368     int   octave;
01369 
01370     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
01371   };
01372 
01373   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointWithScale& p);
01377   struct PointWithScale : public _PointWithScale
01378   {
01379     inline PointWithScale (const _PointWithScale &p)
01380     {
01381       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
01382       scale = p.scale;
01383       angle = p.angle;
01384       response = p.response;
01385       octave = p.octave;
01386     }
01387 
01388     inline PointWithScale ()
01389     {
01390       x = y = z = 0.0f;
01391       scale = 1.0f;
01392       angle = -1.0f;
01393       response = 0.0f;
01394       octave = 0;
01395       data[3] = 1.0f;
01396     }
01397 
01398     inline PointWithScale (float _x, float _y, float _z, float _scale)
01399     {
01400       x = _x;
01401       y = _y;
01402       z = _z;
01403       scale = _scale;
01404       angle = -1.0f;
01405       response = 0.0f;
01406       octave = 0;
01407       data[3] = 1.0f;
01408     }
01409 
01410     inline PointWithScale (float _x, float _y, float _z, float _scale, float _angle, float _response, int _octave)
01411     {
01412       x = _x;
01413       y = _y;
01414       z = _z;
01415       scale = _scale;
01416       angle = _angle;
01417       response = _response;
01418       octave = _octave;
01419       data[3] = 1.0f;
01420     }
01421   
01422     friend std::ostream& operator << (std::ostream& os, const PointWithScale& p);
01423   };
01424 
01425 
01426   struct EIGEN_ALIGN16 _PointSurfel
01427   {
01428     PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
01429     PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
01430     union
01431     {
01432       struct
01433       {
01434         // RGB union
01435         union
01436         {
01437           struct
01438           {
01439             uint8_t b;
01440             uint8_t g;
01441             uint8_t r;
01442             uint8_t a;
01443           };
01444           float rgb;
01445           uint32_t rgba;
01446         };
01447         float radius;
01448         float confidence;
01449         float curvature;
01450       };
01451       float data_c[4];
01452     };
01453     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
01454   };
01455 
01456   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointSurfel& p);
01460   struct PointSurfel : public _PointSurfel
01461   {
01462     inline PointSurfel (const _PointSurfel &p)
01463     {
01464       x = p.x; y = p.y; z = p.z; data[3] = 1.0f;
01465       rgba = p.rgba;
01466       radius = p.radius;
01467       confidence = p.confidence;
01468       curvature = p.curvature;
01469     }
01470 
01471     inline PointSurfel ()
01472     {
01473       x = y = z = 0.0f;
01474       data[3] = 1.0f;
01475       normal_x = normal_y = normal_z = data_n[3] = 0.0f;
01476       rgba = 0;
01477       radius = confidence = curvature = 0.0f;
01478     }
01479   
01480     friend std::ostream& operator << (std::ostream& os, const PointSurfel& p);
01481   };
01482 
01483   template <int N> std::ostream& 
01484   operator << (std::ostream& os, const Histogram<N>& p)
01485   {
01486     for (int i = 0; i < N; ++i)
01487     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < N-1 ? ", " : ")");
01488     return (os);
01489   }
01490 } // End namespace
01491 
01492 // Preserve API for PCL users < 1.4
01493 #include <pcl/common/point_tests.h>
01494 
01495 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:03