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 Willow Garage, Inc. 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: point_types.h 6126 2012-07-03 20:19:58Z aichim $
00037  *
00038  */
00039 #ifndef PCL_DATA_TYPES_H_
00040 #define PCL_DATA_TYPES_H_
00041 
00042 #include <pcl/pcl_macros.h>
00043 #include <pcl/common/eigen.h>
00044 #include <bitset>
00045 #include <vector>
00046 #include <pcl/ros/register_point_struct.h>
00047 
00054 // We're doing a lot of black magic with Boost here, so disable warnings in Maintainer mode, as we will never
00055 // be able to fix them anyway
00056 #if defined _MSC_VER
00057   #pragma warning(disable: 4201)
00058 #endif
00059 
00060 //#pragma warning(push, 1)
00061 #ifdef BUILD_Maintainer
00062 #  if defined __GNUC__
00063 #    include <features.h>
00064 #    if __GNUC_PREREQ(4, 3)
00065 #      pragma GCC diagnostic ignored "-Weffc++"
00066 #      pragma GCC diagnostic ignored "-pedantic"
00067 #    else
00068 #      pragma GCC system_header
00069 #    endif
00070 //#  elif defined _MSC_VER
00071 #  endif
00072 #endif
00073 
00075 namespace pcl
00076 {
00080   struct PointXYZ;
00081 
00085   struct RGB;
00086 
00090   struct PointXYZI;
00091 
00095   struct PointXYZL;
00096 
00100   struct Label;
00101 
00105   struct PointXYZRGBA;
00106 
00110   struct PointXYZRGB;
00111 
00115   struct PointXYZRGBL;
00116 
00120   struct PointXYZHSV;
00121 
00125   struct PointXY;
00126 
00130   struct InterestPoint;
00131 
00135   struct Normal;
00136 
00140   struct Axis;
00141 
00145   struct PointNormal;
00146 
00150   struct PointXYZRGBNormal;
00151 
00155   struct PointXYZINormal;
00156 
00160   struct PointWithRange;
00161 
00165   struct PointWithViewpoint;
00166 
00170   struct MomentInvariants;
00171 
00175   struct PrincipalRadiiRSD;
00176 
00180   struct Boundary;
00181 
00185   struct PrincipalCurvatures;
00186 
00191   struct SHOT;
00192 
00196   struct SHOT352;
00197 
00201   struct SHOT1344;
00202 
00206   struct ReferenceFrame;
00207 
00211   struct ShapeContext;
00212 
00216   struct PFHSignature125;
00217 
00221   struct PFHRGBSignature250;
00222 
00226   struct PPFSignature;
00227 
00231   struct PPFRGBSignature;
00232 
00236   struct NormalBasedSignature12;
00237 
00241   struct FPFHSignature33;
00242 
00246   struct VFHSignature308;
00250   struct ESFSignature640;
00255   struct Narf36;
00256 
00260   typedef std::bitset<32> BorderTraits;
00261 
00265   enum BorderTrait
00266   {
00267     BORDER_TRAIT__OBSTACLE_BORDER, BORDER_TRAIT__SHADOW_BORDER, BORDER_TRAIT__VEIL_POINT,
00268     BORDER_TRAIT__SHADOW_BORDER_TOP, BORDER_TRAIT__SHADOW_BORDER_RIGHT, BORDER_TRAIT__SHADOW_BORDER_BOTTOM,
00269     BORDER_TRAIT__SHADOW_BORDER_LEFT, BORDER_TRAIT__OBSTACLE_BORDER_TOP, BORDER_TRAIT__OBSTACLE_BORDER_RIGHT,
00270     BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM, BORDER_TRAIT__OBSTACLE_BORDER_LEFT, BORDER_TRAIT__VEIL_POINT_TOP,
00271     BORDER_TRAIT__VEIL_POINT_RIGHT, BORDER_TRAIT__VEIL_POINT_BOTTOM, BORDER_TRAIT__VEIL_POINT_LEFT
00272   };
00273 
00277   struct BorderDescription;
00278 
00282   struct IntensityGradient;
00283 
00287   template<int N>
00288   struct Histogram;
00289 
00293   struct PointWithScale;
00294 
00298   struct PointSurfel;
00299 }
00300 
00303 #include <pcl/impl/point_types.hpp>  // Include struct definitions
00304 
00305 // ==============================
00306 // =====POINT_CLOUD_REGISTER=====
00307 // ==============================
00308 
00309 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::RGB,
00310     (uint32_t, rgba, rgba)
00311 )
00312 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZ,
00313     (float, x, x)
00314     (float, y, y)
00315     (float, z, z)
00316 )
00317 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZ, pcl::_PointXYZ)
00318 
00319 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBA,
00320     (float, x, x)
00321     (float, y, y)
00322     (float, z, z)
00323     (uint32_t, rgba, rgba)
00324 )
00325 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBA, pcl::_PointXYZRGBA)
00326 
00327 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGB,
00328     (float, x, x)
00329     (float, y, y)
00330     (float, z, z)
00331     (float, rgb, rgb)
00332 )
00333 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGB, pcl::_PointXYZRGB)
00334 
00335 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBL,
00336     (float, x, x)
00337     (float, y, y)
00338     (float, z, z)
00339     (uint32_t, rgba, rgba)
00340     (uint32_t, label, label)
00341 )
00342 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBL, pcl::_PointXYZRGBL)
00343 
00344 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZHSV,
00345     (float, x, x)
00346     (float, y, y)
00347     (float, z, z)
00348     (float, h, h)
00349     (float, s, s)
00350     (float, v, v)
00351 )
00352 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZHSV, pcl::_PointXYZHSV)
00353 
00354 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXY,
00355     (float, x, x)
00356     (float, y, y)
00357 )
00358 
00359 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::InterestPoint,
00360     (float, x, x)
00361     (float, y, y)
00362     (float, z, z)
00363     (float, strength, strength)
00364 )
00365 
00366 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZI,
00367     (float, x, x)
00368     (float, y, y)
00369     (float, z, z)
00370     (float, intensity, intensity)
00371 )
00372 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZI, pcl::_PointXYZI)
00373 
00374 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZL,
00375     (float, x, x)
00376     (float, y, y)
00377     (float, z, z)
00378     (uint32_t, label, label)
00379 )
00380 
00381 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Label,
00382     (uint32_t, label, label)
00383 )
00384 
00385 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Normal,
00386     (float, normal_x, normal_x)
00387     (float, normal_y, normal_y)
00388     (float, normal_z, normal_z)
00389     (float, curvature, curvature)
00390 )
00391 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Normal, pcl::_Normal)
00392 
00393 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Axis,
00394     (float, normal_x, normal_x)
00395     (float, normal_y, normal_y)
00396     (float, normal_z, normal_z)
00397 )
00398 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Axis, pcl::_Axis)
00399 
00400 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointNormal,
00401     (float, x, x)
00402     (float, y, y)
00403     (float, z, z)
00404     (float, normal_x, normal_x)
00405     (float, normal_y, normal_y)
00406     (float, normal_z, normal_z)
00407     (float, curvature, curvature)
00408 )
00409 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBNormal,
00410     (float, x, x)
00411     (float, y, y)
00412     (float, z, z)
00413     (float, rgb, rgb)
00414     (float, normal_x, normal_x)
00415     (float, normal_y, normal_y)
00416     (float, normal_z, normal_z)
00417     (float, curvature, curvature)
00418 )
00419 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBNormal, pcl::_PointXYZRGBNormal)
00420 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZINormal,
00421     (float, x, x)
00422     (float, y, y)
00423     (float, z, z)
00424     (float, intensity, intensity)
00425     (float, normal_x, normal_x)
00426     (float, normal_y, normal_y)
00427     (float, normal_z, normal_z)
00428     (float, curvature, curvature)
00429 )
00430 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithRange,
00431     (float, x, x)
00432     (float, y, y)
00433     (float, z, z)
00434     (float, range, range)
00435 )
00436 
00437 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointWithViewpoint,
00438     (float, x, x)
00439     (float, y, y)
00440     (float, z, z)
00441     (float, vp_x, vp_x)
00442     (float, vp_y, vp_y)
00443     (float, vp_z, vp_z)
00444 )
00445 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointWithViewpoint, pcl::_PointWithViewpoint)
00446 
00447 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::MomentInvariants,
00448     (float, j1, j1)
00449     (float, j2, j2)
00450     (float, j3, j3)
00451 )
00452 
00453 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PrincipalRadiiRSD,
00454     (float, r_min, r_min)
00455     (float, r_max, r_max)
00456 )
00457 
00458 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Boundary,
00459     (uint8_t, boundary_point, boundary_point)
00460 )
00461 
00462 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PrincipalCurvatures,
00463     (float, principal_curvature_x, principal_curvature_x)
00464     (float, principal_curvature_y, principal_curvature_y)
00465     (float, principal_curvature_z, principal_curvature_z)
00466     (float, pc1, pc1)
00467     (float, pc2, pc2)
00468 )
00469 
00470 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PFHSignature125,
00471     (float[125], histogram, pfh)
00472 )
00473 
00474 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PFHRGBSignature250,
00475     (float[250], histogram, pfhrgb)
00476 )
00477 
00478 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PPFSignature,
00479     (float, f1, f1)
00480     (float, f2, f2)
00481     (float, f3, f3)
00482     (float, f4, f4)
00483     (float, alpha_m, alpha_m)
00484 )
00485 
00486 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PPFRGBSignature,
00487     (float, f1, f1)
00488     (float, f2, f2)
00489     (float, f3, f3)
00490     (float, f4, f4)
00491     (float, r_ratio, r_ratio)
00492     (float, g_ratio, g_ratio)
00493     (float, b_ratio, b_ratio)
00494     (float, alpha_m, alpha_m)
00495 )
00496 
00497 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::NormalBasedSignature12,
00498     (float[12], values, values)
00499 )
00500 
00501 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::SHOT352,
00502     (float[352], descriptor, shot)
00503     (float[9], rf, rf)
00504 )
00505 
00506 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::SHOT1344,
00507     (float[1344], descriptor, shot)
00508     (float[9], rf, rf)
00509 )
00510 
00511 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::FPFHSignature33,
00512     (float[33], histogram, fpfh)
00513 )
00514 
00515 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::VFHSignature308,
00516     (float[308], histogram, vfh)
00517 )
00518 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ESFSignature640,
00519     (float[640], histogram, esf)
00520 )
00521 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Narf36,
00522     (float[36], descriptor, descriptor)
00523 )
00524 
00525 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::GFPFHSignature16,
00526     (float[16], histogram, gfpfh)
00527 )
00528 
00529 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::IntensityGradient,
00530     (float, gradient_x, gradient_x)
00531     (float, gradient_y, gradient_y)
00532     (float, gradient_z, gradient_z)
00533 )
00534 
00535 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithScale,
00536     (float, x, x)
00537     (float, y, y)
00538     (float, z, z)
00539     (float, scale, scale)
00540 )
00541 
00542 POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::PointSurfel,
00543     (float, x, x)
00544     (float, y, y)
00545     (float, z, z)
00546     (float, normal_x, normal_x)
00547     (float, normal_y, normal_y)
00548     (float, normal_z, normal_z)
00549     (uint32_t, rgba, rgba)
00550     (float, radius, radius)
00551     (float, confidence, confidence)
00552     (float, curvature, curvature)
00553 )
00554 
00555 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_ReferenceFrame,
00556     (float[3], x_axis, x_axis)
00557     (float[3], y_axis, y_axis)
00558     (float[3], z_axis, z_axis)
00559     //(float, confidence, confidence)
00560 )
00561 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::ReferenceFrame, pcl::_ReferenceFrame)
00562 
00563 //POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::BorderDescription,
00564 //                                  (int, x, x)
00565 //                                  (int, y, y)
00566 //                                  (uint32_t, traits, traits)
00567 //)
00568 
00569 namespace pcl {
00570   // Allow float 'rgb' data to match to the newer uint32 'rgba' tag. This is so
00571   // you can load old 'rgb' PCD files into e.g. a PointCloud<PointXYZRGBA>.
00572   template<typename PointT>
00573   struct FieldMatches<PointT, fields::rgba>
00574   {
00575     bool operator() (const sensor_msgs::PointField& field)
00576     {
00577       if (field.name == "rgb")
00578       {
00579         return (field.datatype == sensor_msgs::PointField::FLOAT32 &&
00580                 field.count == 1);
00581       }
00582       else
00583       {
00584         return (field.name == traits::name<PointT, fields::rgba>::value &&
00585                 field.datatype == traits::datatype<PointT, fields::rgba>::value &&
00586                 field.count == traits::datatype<PointT, fields::rgba>::size);
00587       }
00588     }
00589   };
00590 } // namespace pcl
00591 
00592 #if defined _MSC_VER
00593   #pragma warning(default: 4201)
00594 #endif
00595 //#pragma warning(pop)
00596 #ifdef BUILD_Maintainer
00597 #  if defined __GNUC__
00598 #    if __GNUC_PREREQ(4, 3)
00599 #      pragma GCC diagnostic warning "-Weffc++"
00600 #      pragma GCC diagnostic warning "-pedantic"
00601 #    endif
00602 //#  elif defined _MSC_VER
00603 #  endif
00604 #endif
00605 
00606 #endif  //#ifndef PCL_DATA_TYPES_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:19