point_types.h
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-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 #ifndef PCL_DATA_TYPES_H_
00040 #define PCL_DATA_TYPES_H_
00041 
00042 #include <pcl/pcl_macros.h>
00043 #include <bitset>
00044 #include <pcl/register_point_struct.h>
00045 
00052 // We're doing a lot of black magic with Boost here, so disable warnings in Maintainer mode, as we will never
00053 // be able to fix them anyway
00054 #if defined _MSC_VER
00055   #pragma warning(disable: 4201)
00056 #endif
00057 //#pragma warning(push, 1)
00058 #if defined __GNUC__
00059 #  pragma GCC system_header
00060 #endif
00061 
00063 namespace pcl
00064 {
00068   struct PointXYZ;
00069 
00073   struct RGB;
00074 
00078   struct Intensity;
00079 
00083   struct Intensity8u;
00084 
00088   struct Intensity32u;
00089 
00093   struct PointXYZI;
00094 
00098   struct PointXYZL;
00099 
00103   struct Label;
00104 
00108   struct PointXYZRGBA;
00109 
00113   struct PointXYZRGB;
00114 
00118   struct PointXYZRGBL;
00119 
00123   struct PointXYZHSV;
00124 
00128   struct PointXY;
00129 
00133   struct PointUV;
00134 
00138   struct InterestPoint;
00139 
00143   struct Normal;
00144 
00148   struct Axis;
00149 
00153   struct PointNormal;
00154 
00158   struct PointXYZRGBNormal;
00159 
00163   struct PointXYZINormal;
00164 
00168   struct PointWithRange;
00169 
00173   struct PointWithViewpoint;
00174 
00178   struct MomentInvariants;
00179 
00183   struct PrincipalRadiiRSD;
00184 
00188   struct Boundary;
00189 
00193   struct PrincipalCurvatures;
00194 
00198   struct SHOT352;
00199 
00203   struct SHOT1344;
00204 
00208   struct ReferenceFrame;
00209 
00213   struct ShapeContext1980;
00214 
00218   struct PFHSignature125;
00219 
00223   struct PFHRGBSignature250;
00224 
00228   struct PPFSignature;
00229 
00233   struct PPFRGBSignature;
00234 
00238   struct NormalBasedSignature12;
00239 
00243   struct FPFHSignature33;
00244   
00248   struct VFHSignature308;
00249   
00253   struct ESFSignature640;
00254 
00258   struct GFPFHSignature16;
00259 
00263   struct Narf36;
00264 
00268   typedef std::bitset<32> BorderTraits;
00269 
00273   enum BorderTrait
00274   {
00275     BORDER_TRAIT__OBSTACLE_BORDER, BORDER_TRAIT__SHADOW_BORDER, BORDER_TRAIT__VEIL_POINT,
00276     BORDER_TRAIT__SHADOW_BORDER_TOP, BORDER_TRAIT__SHADOW_BORDER_RIGHT, BORDER_TRAIT__SHADOW_BORDER_BOTTOM,
00277     BORDER_TRAIT__SHADOW_BORDER_LEFT, BORDER_TRAIT__OBSTACLE_BORDER_TOP, BORDER_TRAIT__OBSTACLE_BORDER_RIGHT,
00278     BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM, BORDER_TRAIT__OBSTACLE_BORDER_LEFT, BORDER_TRAIT__VEIL_POINT_TOP,
00279     BORDER_TRAIT__VEIL_POINT_RIGHT, BORDER_TRAIT__VEIL_POINT_BOTTOM, BORDER_TRAIT__VEIL_POINT_LEFT
00280   };
00281 
00285   struct BorderDescription;
00286 
00290   struct IntensityGradient;
00291 
00295   template<int N>
00296   struct Histogram;
00297 
00301   struct PointWithScale;
00302 
00306   struct PointSurfel;
00307 }
00308 
00311 #include <pcl/impl/point_types.hpp>  // Include struct definitions
00312 
00313 // ==============================
00314 // =====POINT_CLOUD_REGISTER=====
00315 // ==============================
00316 
00317 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_RGB,
00318     (uint32_t, rgba, rgba)
00319 )
00320 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::RGB, pcl::_RGB)
00321 
00322 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Intensity,
00323     (float, intensity, intensity)
00324 )
00325 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Intensity, pcl::_Intensity)
00326 
00327 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Intensity8u,
00328     (uint8_t, intensity, intensity)
00329 )
00330 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Intensity8u, pcl::_Intensity8u)
00331 
00332 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Intensity32u,
00333     (uint32_t, intensity, intensity)
00334 )
00335 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Intensity32u, pcl::_Intensity32u)
00336 
00337 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZ,
00338     (float, x, x)
00339     (float, y, y)
00340     (float, z, z)
00341 )
00342 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZ, pcl::_PointXYZ)
00343 
00344 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBA,
00345     (float, x, x)
00346     (float, y, y)
00347     (float, z, z)
00348     (uint32_t, rgba, rgba)
00349 )
00350 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBA, pcl::_PointXYZRGBA)
00351 
00352 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGB,
00353     (float, x, x)
00354     (float, y, y)
00355     (float, z, z)
00356     (float, rgb, rgb)
00357 )
00358 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGB, pcl::_PointXYZRGB)
00359 
00360 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBL,
00361     (float, x, x)
00362     (float, y, y)
00363     (float, z, z)
00364     (uint32_t, rgba, rgba)
00365     (uint32_t, label, label)
00366 )
00367 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBL, pcl::_PointXYZRGBL)
00368 
00369 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZHSV,
00370     (float, x, x)
00371     (float, y, y)
00372     (float, z, z)
00373     (float, h, h)
00374     (float, s, s)
00375     (float, v, v)
00376 )
00377 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZHSV, pcl::_PointXYZHSV)
00378 
00379 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXY,
00380     (float, x, x)
00381     (float, y, y)
00382 )
00383 
00384 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointUV,
00385     (float, u, u)
00386     (float, v, v)
00387 )
00388 
00389 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::InterestPoint,
00390     (float, x, x)
00391     (float, y, y)
00392     (float, z, z)
00393     (float, strength, strength)
00394 )
00395 
00396 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZI,
00397     (float, x, x)
00398     (float, y, y)
00399     (float, z, z)
00400     (float, intensity, intensity)
00401 )
00402 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZI, pcl::_PointXYZI)
00403 
00404 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZL,
00405     (float, x, x)
00406     (float, y, y)
00407     (float, z, z)
00408     (uint32_t, label, label)
00409 )
00410 
00411 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Label,
00412     (uint32_t, label, label)
00413 )
00414 
00415 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Normal,
00416     (float, normal_x, normal_x)
00417     (float, normal_y, normal_y)
00418     (float, normal_z, normal_z)
00419     (float, curvature, curvature)
00420 )
00421 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Normal, pcl::_Normal)
00422 
00423 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Axis,
00424     (float, normal_x, normal_x)
00425     (float, normal_y, normal_y)
00426     (float, normal_z, normal_z)
00427 )
00428 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Axis, pcl::_Axis)
00429 
00430 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointNormal,
00431     (float, x, x)
00432     (float, y, y)
00433     (float, z, z)
00434     (float, normal_x, normal_x)
00435     (float, normal_y, normal_y)
00436     (float, normal_z, normal_z)
00437     (float, curvature, curvature)
00438 )
00439 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBNormal,
00440     (float, x, x)
00441     (float, y, y)
00442     (float, z, z)
00443     (float, rgb, rgb)
00444     (float, normal_x, normal_x)
00445     (float, normal_y, normal_y)
00446     (float, normal_z, normal_z)
00447     (float, curvature, curvature)
00448 )
00449 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBNormal, pcl::_PointXYZRGBNormal)
00450 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZINormal,
00451     (float, x, x)
00452     (float, y, y)
00453     (float, z, z)
00454     (float, intensity, intensity)
00455     (float, normal_x, normal_x)
00456     (float, normal_y, normal_y)
00457     (float, normal_z, normal_z)
00458     (float, curvature, curvature)
00459 )
00460 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithRange,
00461     (float, x, x)
00462     (float, y, y)
00463     (float, z, z)
00464     (float, range, range)
00465 )
00466 
00467 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointWithViewpoint,
00468     (float, x, x)
00469     (float, y, y)
00470     (float, z, z)
00471     (float, vp_x, vp_x)
00472     (float, vp_y, vp_y)
00473     (float, vp_z, vp_z)
00474 )
00475 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointWithViewpoint, pcl::_PointWithViewpoint)
00476 
00477 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::MomentInvariants,
00478     (float, j1, j1)
00479     (float, j2, j2)
00480     (float, j3, j3)
00481 )
00482 
00483 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PrincipalRadiiRSD,
00484     (float, r_min, r_min)
00485     (float, r_max, r_max)
00486 )
00487 
00488 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Boundary,
00489     (uint8_t, boundary_point, boundary_point)
00490 )
00491 
00492 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PrincipalCurvatures,
00493     (float, principal_curvature_x, principal_curvature_x)
00494     (float, principal_curvature_y, principal_curvature_y)
00495     (float, principal_curvature_z, principal_curvature_z)
00496     (float, pc1, pc1)
00497     (float, pc2, pc2)
00498 )
00499 
00500 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PFHSignature125,
00501     (float[125], histogram, pfh)
00502 )
00503 
00504 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PFHRGBSignature250,
00505     (float[250], histogram, pfhrgb)
00506 )
00507 
00508 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PPFSignature,
00509     (float, f1, f1)
00510     (float, f2, f2)
00511     (float, f3, f3)
00512     (float, f4, f4)
00513     (float, alpha_m, alpha_m)
00514 )
00515 
00516 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PPFRGBSignature,
00517     (float, f1, f1)
00518     (float, f2, f2)
00519     (float, f3, f3)
00520     (float, f4, f4)
00521     (float, r_ratio, r_ratio)
00522     (float, g_ratio, g_ratio)
00523     (float, b_ratio, b_ratio)
00524     (float, alpha_m, alpha_m)
00525 )
00526 
00527 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::NormalBasedSignature12,
00528     (float[12], values, values)
00529 )
00530 
00531 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ShapeContext1980,
00532     (float[1980], descriptor, shape_context)
00533     (float[9], rf, rf)
00534 )
00535 
00536 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::SHOT352,
00537     (float[352], descriptor, shot)
00538     (float[9], rf, rf)
00539 )
00540 
00541 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::SHOT1344,
00542     (float[1344], descriptor, shot)
00543     (float[9], rf, rf)
00544 )
00545 
00546 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::FPFHSignature33,
00547     (float[33], histogram, fpfh)
00548 )
00549 
00550 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::VFHSignature308,
00551     (float[308], histogram, vfh)
00552 )
00553 
00554 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ESFSignature640,
00555     (float[640], histogram, esf)
00556 )
00557 
00558 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Narf36,
00559     (float[36], descriptor, descriptor)
00560 )
00561 
00562 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::GFPFHSignature16,
00563     (float[16], histogram, gfpfh)
00564 )
00565 
00566 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::IntensityGradient,
00567     (float, gradient_x, gradient_x)
00568     (float, gradient_y, gradient_y)
00569     (float, gradient_z, gradient_z)
00570 )
00571 
00572 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithScale,
00573     (float, x, x)
00574     (float, y, y)
00575     (float, z, z)
00576     (float, scale, scale)
00577 )
00578 
00579 POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::PointSurfel,
00580     (float, x, x)
00581     (float, y, y)
00582     (float, z, z)
00583     (float, normal_x, normal_x)
00584     (float, normal_y, normal_y)
00585     (float, normal_z, normal_z)
00586     (uint32_t, rgba, rgba)
00587     (float, radius, radius)
00588     (float, confidence, confidence)
00589     (float, curvature, curvature)
00590 )
00591 
00592 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_ReferenceFrame,
00593     (float[3], x_axis, x_axis)
00594     (float[3], y_axis, y_axis)
00595     (float[3], z_axis, z_axis)
00596 )
00597 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::ReferenceFrame, pcl::_ReferenceFrame)
00598 
00599 namespace pcl 
00600 {
00601   // Allow float 'rgb' data to match to the newer uint32 'rgba' tag. This is so
00602   // you can load old 'rgb' PCD files into e.g. a PointCloud<PointXYZRGBA>.
00603   template<typename PointT>
00604   struct FieldMatches<PointT, fields::rgba>
00605   {
00606     bool operator() (const pcl::PCLPointField& field)
00607     {
00608       if (field.name == "rgb")
00609       {
00610         return (field.datatype == pcl::PCLPointField::FLOAT32 &&
00611                 field.count == 1);
00612       }
00613       else
00614       {
00615         return (field.name == traits::name<PointT, fields::rgba>::value &&
00616                 field.datatype == traits::datatype<PointT, fields::rgba>::value &&
00617                 field.count == traits::datatype<PointT, fields::rgba>::size);
00618       }
00619     }
00620   };
00621   template<typename PointT>
00622   struct FieldMatches<PointT, fields::rgb>
00623   {
00624     bool operator() (const pcl::PCLPointField& field)
00625     {
00626       if (field.name == "rgba")
00627       {
00628         return (field.datatype == pcl::PCLPointField::UINT32 &&
00629                 field.count == 1);
00630       }
00631       else
00632       {
00633         return (field.name == traits::name<PointT, fields::rgb>::value &&
00634                 field.datatype == traits::datatype<PointT, fields::rgb>::value &&
00635                 field.count == traits::datatype<PointT, fields::rgb>::size);
00636       }
00637     }
00638   };
00639 } // namespace pcl
00640 
00641 #if defined _MSC_VER
00642   #pragma warning(default: 4201)
00643 #endif
00644 //#pragma warning(pop)
00645 
00646 #endif  //#ifndef PCL_DATA_TYPES_H_


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