register_point_struct.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: register_point_struct.h 6126 2012-07-03 20:19:58Z aichim $
00037  *
00038  */
00039 
00040 #ifndef PCL_REGISTER_POINT_STRUCT_H_
00041 #define PCL_REGISTER_POINT_STRUCT_H_
00042 
00043 #include <pcl/point_traits.h>
00044 
00045 #include <boost/mpl/vector.hpp>
00046 #include <boost/mpl/for_each.hpp>
00047 #include <boost/mpl/assert.hpp>
00048 #include <boost/preprocessor/seq/enum.hpp>
00049 #include <boost/preprocessor/seq/for_each.hpp>
00050 #include <boost/preprocessor/seq/transform.hpp>
00051 #include <boost/preprocessor/cat.hpp>
00052 #include <boost/preprocessor/repetition/repeat_from_to.hpp>
00053 #include <boost/type_traits/is_pod.hpp>
00054 #include <stddef.h> //offsetof
00055 
00056 // Must be used in global namespace with name fully qualified
00057 #define POINT_CLOUD_REGISTER_POINT_STRUCT(name, fseq)               \
00058   POINT_CLOUD_REGISTER_POINT_STRUCT_I(name,                         \
00059     BOOST_PP_CAT(POINT_CLOUD_REGISTER_POINT_STRUCT_X fseq, 0))      \
00060   /***/
00061 
00062 #define POINT_CLOUD_REGISTER_POINT_WRAPPER(wrapper, pod)    \
00063   BOOST_MPL_ASSERT_MSG(sizeof(wrapper) == sizeof(pod), POINT_WRAPPER_AND_POD_TYPES_HAVE_DIFFERENT_SIZES, (wrapper&, pod&)); \
00064   namespace pcl {                                           \
00065     namespace traits {                                      \
00066       template<> struct POD<wrapper> { typedef pod type; }; \
00067     }                                                       \
00068   }                                                         \
00069   /***/
00070 
00071 // These macros help transform the unusual data structure (type, name, tag)(type, name, tag)...
00072 // into a proper preprocessor sequence of 3-tuples ((type, name, tag))((type, name, tag))...
00073 #define POINT_CLOUD_REGISTER_POINT_STRUCT_X(type, name, tag)            \
00074   ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_Y
00075 #define POINT_CLOUD_REGISTER_POINT_STRUCT_Y(type, name, tag)            \
00076   ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_X
00077 #define POINT_CLOUD_REGISTER_POINT_STRUCT_X0
00078 #define POINT_CLOUD_REGISTER_POINT_STRUCT_Y0
00079 
00080 // Construct type traits given full sequence of (type, name, tag) triples
00081 //  BOOST_MPL_ASSERT_MSG(boost::is_pod<name>::value,                    
00082 //                       REGISTERED_POINT_TYPE_MUST_BE_PLAIN_OLD_DATA, (name)); 
00083 #define POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, seq)                           \
00084   namespace pcl                                                                  \
00085   {                                                                              \
00086     namespace fields                                                             \
00087     {                                                                            \
00088       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_TAG, name, seq)           \
00089     }                                                                            \
00090     namespace traits                                                             \
00091     {                                                                            \
00092       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_NAME, name, seq)          \
00093       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_OFFSET, name, seq)        \
00094       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_DATATYPE, name, seq)      \
00095       POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, POINT_CLOUD_EXTRACT_TAGS(seq)) \
00096     }                                                                            \
00097   }                                                                              \
00098   /***/
00099 
00100 #define POINT_CLOUD_REGISTER_FIELD_TAG(r, name, elem)   \
00101   struct BOOST_PP_TUPLE_ELEM(3, 2, elem);               \
00102   /***/
00103 
00104 #define POINT_CLOUD_REGISTER_FIELD_NAME(r, point, elem)                 \
00105   template<int dummy>                                                   \
00106   struct name<point, pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem), dummy> \
00107   {                                                                     \
00108     static const char value[];                                          \
00109   };                                                                    \
00110                                                                         \
00111   template<int dummy>                                                   \
00112   const char name<point,                                                \
00113                   pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem),         \
00114                   dummy>::value[] =                                     \
00115     BOOST_PP_STRINGIZE(BOOST_PP_TUPLE_ELEM(3, 2, elem));                \
00116   /***/
00117 
00118 #define POINT_CLOUD_REGISTER_FIELD_OFFSET(r, name, elem)                \
00119   template<> struct offset<name, pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem)> \
00120   {                                                                     \
00121     static const size_t value = offsetof(name, BOOST_PP_TUPLE_ELEM(3, 1, elem)); \
00122   };                                                                    \
00123   /***/
00124 
00125 // \note: the mpl::identity weirdness is to support array types without requiring the
00126 // user to wrap them. The basic problem is:
00127 // typedef float[81] type; // SYNTAX ERROR!
00128 // typedef float type[81]; // OK, can now use "type" as a synonym for float[81]
00129 #define POINT_CLOUD_REGISTER_FIELD_DATATYPE(r, name, elem)              \
00130   template<> struct datatype<name, pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem)> \
00131   {                                                                     \
00132     typedef boost::mpl::identity<BOOST_PP_TUPLE_ELEM(3, 0, elem)>::type type; \
00133     typedef decomposeArray<type> decomposed;                            \
00134     static const uint8_t value = asEnum<decomposed::type>::value;       \
00135     static const uint32_t size = decomposed::value;                     \
00136   };                                                                    \
00137   /***/
00138 
00139 #define POINT_CLOUD_TAG_OP(s, data, elem) pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem)
00140 
00141 #define POINT_CLOUD_EXTRACT_TAGS(seq) BOOST_PP_SEQ_TRANSFORM(POINT_CLOUD_TAG_OP, _, seq)
00142 
00143 #define POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, seq)        \
00144   template<> struct fieldList<name>                             \
00145   {                                                             \
00146     typedef boost::mpl::vector<BOOST_PP_SEQ_ENUM(seq)> type;    \
00147   };                                                            \
00148   /***/
00149 
00150 // Disabling barely-used Fusion registration of point types for now.
00151 #if 0
00152 #define POINT_CLOUD_EXPAND_TAG_OP(s, data, elem)                \
00153   (boost::mpl::identity<BOOST_PP_TUPLE_ELEM(3, 0, elem)>::type, \
00154    BOOST_PP_TUPLE_ELEM(3, 1, elem),                             \
00155    pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem))                \
00156   /***/
00157 
00158 #define POINT_CLOUD_EXPAND_TAGS(seq) BOOST_PP_SEQ_TRANSFORM(POINT_CLOUD_EXPAND_TAG_OP, _, seq)
00159 
00160 #define POINT_CLOUD_REGISTER_WITH_FUSION(name, seq)                     \
00161   BOOST_FUSION_ADAPT_ASSOC_STRUCT_I(name, POINT_CLOUD_EXPAND_TAGS(seq)) \
00162   /***/
00163 #endif
00164 
00165 #endif  //#ifndef PCL_REGISTER_POINT_STRUCT_H_


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