point_traits.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-2012, 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_traits.h 5286 2012-03-25 01:43:57Z nizar $
00037  *
00038  */
00039 
00040 #ifndef PCL_POINT_TRAITS_H_
00041 #define PCL_POINT_TRAITS_H_
00042 
00043 #include <sensor_msgs/PointField.h>
00044 #include <boost/type_traits/remove_all_extents.hpp>
00045 #include <boost/type_traits/is_same.hpp>
00046 #include <boost/mpl/assert.hpp>
00047 #include <boost/mpl/bool.hpp>
00048 
00049 // We're doing a lot of black magic with Boost here, so disable warnings in Maintainer mode, as we will never
00050 // be able to fix them anyway
00051 #ifdef BUILD_Maintainer
00052 #  if defined __GNUC__
00053 #    include <features.h>
00054 #    if __GNUC_PREREQ(4, 3)
00055 #      pragma GCC diagnostic ignored "-Weffc++"
00056 #      pragma GCC diagnostic ignored "-pedantic"
00057 #    else
00058 #      pragma GCC system_header
00059 #    endif
00060 #  elif defined _MSC_VER
00061 #    pragma warning(push, 1)
00062 #  endif
00063 #endif
00064 
00065 namespace pcl
00066 {
00067 
00068   namespace fields
00069   {
00070     // Tag types get put in this namespace
00071   }
00072 
00073   namespace traits
00074   {
00075     // Metafunction to return enum value representing a type
00076     template<typename T> struct asEnum {};
00077     template<> struct asEnum<int8_t>   { static const uint8_t value = sensor_msgs::PointField::INT8;    };
00078     template<> struct asEnum<uint8_t>  { static const uint8_t value = sensor_msgs::PointField::UINT8;   };
00079     template<> struct asEnum<int16_t>  { static const uint8_t value = sensor_msgs::PointField::INT16;   };
00080     template<> struct asEnum<uint16_t> { static const uint8_t value = sensor_msgs::PointField::UINT16;  };
00081     template<> struct asEnum<int32_t>  { static const uint8_t value = sensor_msgs::PointField::INT32;   };
00082     template<> struct asEnum<uint32_t> { static const uint8_t value = sensor_msgs::PointField::UINT32;  };
00083     template<> struct asEnum<float>    { static const uint8_t value = sensor_msgs::PointField::FLOAT32; };
00084     template<> struct asEnum<double>   { static const uint8_t value = sensor_msgs::PointField::FLOAT64; };
00085 
00086     // Metafunction to return type of enum value
00087     template<int> struct asType {};
00088     template<> struct asType<sensor_msgs::PointField::INT8>    { typedef int8_t   type; };
00089     template<> struct asType<sensor_msgs::PointField::UINT8>   { typedef uint8_t  type; };
00090     template<> struct asType<sensor_msgs::PointField::INT16>   { typedef int16_t  type; };
00091     template<> struct asType<sensor_msgs::PointField::UINT16>  { typedef uint16_t type; };
00092     template<> struct asType<sensor_msgs::PointField::INT32>   { typedef int32_t  type; };
00093     template<> struct asType<sensor_msgs::PointField::UINT32>  { typedef uint32_t type; };
00094     template<> struct asType<sensor_msgs::PointField::FLOAT32> { typedef float    type; };
00095     template<> struct asType<sensor_msgs::PointField::FLOAT64> { typedef double   type; };
00096 
00097     // Metafunction to decompose a type (possibly of array of any number of dimensions) into
00098     // its scalar type and total number of elements.
00099     template<typename T> struct decomposeArray
00100     {
00101       typedef typename boost::remove_all_extents<T>::type type;
00102       static const uint32_t value = sizeof(T) / sizeof(type);
00103     };
00104 
00105     // For non-POD point types, this is specialized to return the corresponding POD type.
00106     template<typename PointT>
00107     struct POD
00108     {
00109       typedef PointT type;
00110     };
00111 
00112     // name
00113     /* This really only depends on Tag, but we go through some gymnastics to avoid ODR violations.
00114        We template it on the point type PointT to avoid ODR violations when registering multiple
00115        point types with shared tags.
00116        The dummy parameter is so we can partially specialize name on PointT and Tag but leave it
00117        templated on dummy. Each specialization declares a static char array containing the tag
00118        name. The definition of the static member would conflict when linking multiple translation
00119        units that include the point type registration. But when the static member definition is
00120        templated (on dummy), we sidestep the ODR issue.
00121     */
00122     template<class PointT, typename Tag, int dummy = 0>
00123     struct name : name<typename POD<PointT>::type, Tag, dummy>
00124     {
00125       // Contents of specialization:
00126       // static const char value[];
00127 
00128       // Avoid infinite compile-time recursion
00129       BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00130                            POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00131     };
00132 
00133     // offset
00134     template<class PointT, typename Tag>
00135     struct offset : offset<typename POD<PointT>::type, Tag>
00136     {
00137       // Contents of specialization:
00138       // static const size_t value;
00139 
00140       // Avoid infinite compile-time recursion
00141       BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00142                            POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00143     };
00144 
00145     // datatype
00146     template<class PointT, typename Tag>
00147     struct datatype : datatype<typename POD<PointT>::type, Tag>
00148     {
00149       // Contents of specialization:
00150       // typedef ... type;
00151       // static const uint8_t value;
00152       // static const uint32_t size;
00153 
00154       // Avoid infinite compile-time recursion
00155       BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00156                            POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00157     };
00158 
00159     // fields
00160     template<typename PointT>
00161     struct fieldList : fieldList<typename POD<PointT>::type>
00162     {
00163       // Contents of specialization:
00164       // typedef boost::mpl::vector<...> type;
00165 
00166       // Avoid infinite compile-time recursion
00167       BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00168                            POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00169     };
00170 
00171     /*
00172       At least on GCC 4.4.3, but not later versions, some valid usages of the above traits for
00173       non-POD (but registered) point types fail with:
00174       error: ‘!(bool)mpl_::bool_<false>::value’ is not a valid template argument for type ‘bool’ because it is a non-constant expression
00175 
00176       "Priming the pump" with the trivial assertion below somehow fixes the problem...
00177      */
00178     //BOOST_MPL_ASSERT_MSG((!bool (mpl_::bool_<false>::value)), WTF_GCC443, (bool));
00179     BOOST_MPL_ASSERT_MSG((!bool (boost::mpl::bool_<false>::value)), WTF_GCC443, (bool));
00180   } //namespace traits
00181 
00182   // Return true if the PointField matches the expected name and data type.
00183   // Written as a struct to allow partially specializing on Tag.
00184   template<typename PointT, typename Tag>
00185   struct FieldMatches
00186   {
00187     bool operator() (const sensor_msgs::PointField& field)
00188     {
00189       return (field.name == traits::name<PointT, Tag>::value &&
00190               field.datatype == traits::datatype<PointT, Tag>::value &&
00191               field.count == traits::datatype<PointT, Tag>::size);
00192     }
00193   };
00194 
00196   template <typename PointInT, typename OutT>
00197   struct CopyIfFieldExists
00198   {
00199     typedef typename traits::POD<PointInT>::type Pod;
00200 
00207     CopyIfFieldExists (const PointInT &pt,
00208                        const std::string &field,
00209                        bool &exists,
00210                        OutT &value)
00211       : pt_ (reinterpret_cast<const Pod&>(pt)), name_ (field), exists_ (exists), value_ (value)
00212     {
00213       exists_ = false;
00214     }
00215 
00221     CopyIfFieldExists (const PointInT &pt,
00222                        const std::string &field,
00223                        OutT &value)
00224       : pt_ (reinterpret_cast<const Pod&>(pt)), name_ (field), exists_ (exists_tmp_), value_ (value)
00225     {
00226     }
00227 
00229     template <typename Key> inline void
00230     operator() ()
00231     {
00232       if (name_ == pcl::traits::name<PointInT, Key>::value)
00233       {
00234         exists_ = true;
00235         typedef typename pcl::traits::datatype<PointInT, Key>::type T;
00236         const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&pt_) + pcl::traits::offset<PointInT, Key>::value;
00237         value_ = static_cast<OutT> (*reinterpret_cast<const T*>(data_ptr));
00238       }
00239     }
00240 
00241     private:
00242       const Pod &pt_;
00243       const std::string &name_;
00244       bool &exists_;
00245       // Bogus entry
00246       bool exists_tmp_;
00247       OutT &value_;
00248   };
00249 
00251   template <typename PointOutT, typename InT>
00252   struct SetIfFieldExists
00253   {
00254     typedef typename traits::POD<PointOutT>::type Pod;
00255 
00261     SetIfFieldExists (PointOutT &pt,
00262                       const std::string &field,
00263                       const InT &value)
00264       : pt_ (reinterpret_cast<Pod&>(pt)), name_ (field), value_ (value)
00265     {
00266     }
00267 
00269     template <typename Key> inline void
00270     operator() ()
00271     {
00272       if (name_ == pcl::traits::name<PointOutT, Key>::value)
00273       {
00274         typedef typename pcl::traits::datatype<PointOutT, Key>::type T;
00275         uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&pt_) + pcl::traits::offset<PointOutT, Key>::value;
00276         *reinterpret_cast<T*>(data_ptr) = static_cast<T> (value_);
00277       }
00278     }
00279 
00280     private:
00281       Pod &pt_;
00282       const std::string &name_;
00283       const InT &value_;
00284   };
00285 }
00286 
00287 #ifdef BUILD_Maintainer
00288 #  if defined __GNUC__
00289 #    if __GNUC_PREREQ(4, 3)
00290 #      pragma GCC diagnostic warning "-Weffc++"
00291 #      pragma GCC diagnostic warning "-pedantic"
00292 #    endif
00293 #  elif defined _MSC_VER
00294 #    pragma warning(pop)
00295 #  endif
00296 #endif
00297 
00298 #endif  //#ifndef PCL_POINT_TRAITS_H_


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