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  *  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  * $Id$
00038  *
00039  */
00040 
00041 #ifndef PCL_REGISTER_POINT_STRUCT_H_
00042 #define PCL_REGISTER_POINT_STRUCT_H_
00043 
00044 #ifdef __GNUC__
00045 #pragma GCC system_header
00046 #endif
00047 
00048 #if defined _MSC_VER
00049   #pragma warning (push, 2)
00050   // 4244 : conversion from 'type1' to 'type2', possible loss of data
00051   #pragma warning (disable: 4244)
00052 #endif
00053 
00054 #include <pcl/pcl_macros.h>
00055 #include <pcl/point_traits.h>
00056 #include <boost/mpl/vector.hpp>
00057 #include <boost/preprocessor/seq/enum.hpp>
00058 #include <boost/preprocessor/seq/for_each.hpp>
00059 #include <boost/preprocessor/seq/transform.hpp>
00060 #include <boost/preprocessor/cat.hpp>
00061 #include <boost/preprocessor/comparison.hpp>
00062 #include <boost/utility.hpp>
00063 //https://bugreports.qt-project.org/browse/QTBUG-22829
00064 #ifndef Q_MOC_RUN
00065 #include <boost/type_traits.hpp>
00066 #endif
00067 #include <stddef.h> //offsetof
00068 
00069 // Must be used in global namespace with name fully qualified
00070 #define POINT_CLOUD_REGISTER_POINT_STRUCT(name, fseq)               \
00071   POINT_CLOUD_REGISTER_POINT_STRUCT_I(name,                         \
00072     BOOST_PP_CAT(POINT_CLOUD_REGISTER_POINT_STRUCT_X fseq, 0))      \
00073   /***/
00074 
00075 #define POINT_CLOUD_REGISTER_POINT_WRAPPER(wrapper, pod)    \
00076   BOOST_MPL_ASSERT_MSG(sizeof(wrapper) == sizeof(pod), POINT_WRAPPER_AND_POD_TYPES_HAVE_DIFFERENT_SIZES, (wrapper&, pod&)); \
00077   namespace pcl {                                           \
00078     namespace traits {                                      \
00079       template<> struct POD<wrapper> { typedef pod type; }; \
00080     }                                                       \
00081   }                                                         \
00082   /***/
00083 
00084 // These macros help transform the unusual data structure (type, name, tag)(type, name, tag)...
00085 // into a proper preprocessor sequence of 3-tuples ((type, name, tag))((type, name, tag))...
00086 #define POINT_CLOUD_REGISTER_POINT_STRUCT_X(type, name, tag)            \
00087   ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_Y
00088 #define POINT_CLOUD_REGISTER_POINT_STRUCT_Y(type, name, tag)            \
00089   ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_X
00090 #define POINT_CLOUD_REGISTER_POINT_STRUCT_X0
00091 #define POINT_CLOUD_REGISTER_POINT_STRUCT_Y0
00092 
00093 namespace pcl
00094 {
00095   namespace traits
00096   {
00097     template<typename T> inline
00098     typename boost::disable_if_c<boost::is_array<T>::value>::type
00099     plus (T &l, const T &r)
00100     {
00101       l += r;
00102     }
00103 
00104     template<typename T> inline
00105     typename boost::enable_if_c<boost::is_array<T>::value>::type
00106     plus (typename boost::remove_const<T>::type &l, const T &r)
00107     {
00108       typedef typename boost::remove_all_extents<T>::type type;
00109       static const uint32_t count = sizeof (T) / sizeof (type);
00110       for (int i = 0; i < count; ++i)
00111         l[i] += r[i];
00112     }
00113 
00114     template<typename T1, typename T2> inline
00115     typename boost::disable_if_c<boost::is_array<T1>::value>::type
00116     plusscalar (T1 &p, const T2 &scalar)
00117     {
00118       p += scalar;
00119     }
00120 
00121     template<typename T1, typename T2> inline
00122     typename boost::enable_if_c<boost::is_array<T1>::value>::type
00123     plusscalar (T1 &p, const T2 &scalar)
00124     {
00125       typedef typename boost::remove_all_extents<T1>::type type;
00126       static const uint32_t count = sizeof (T1) / sizeof (type);
00127       for (int i = 0; i < count; ++i)
00128         p[i] += scalar;
00129     }
00130 
00131     template<typename T> inline
00132     typename boost::disable_if_c<boost::is_array<T>::value>::type
00133     minus (T &l, const T &r)
00134     {
00135       l -= r;
00136     }
00137 
00138     template<typename T> inline
00139     typename boost::enable_if_c<boost::is_array<T>::value>::type
00140     minus (typename boost::remove_const<T>::type &l, const T &r)
00141     {
00142       typedef typename boost::remove_all_extents<T>::type type;
00143       static const uint32_t count = sizeof (T) / sizeof (type);
00144       for (int i = 0; i < count; ++i)
00145         l[i] -= r[i];
00146     }
00147 
00148     template<typename T1, typename T2> inline
00149     typename boost::disable_if_c<boost::is_array<T1>::value>::type
00150     minusscalar (T1 &p, const T2 &scalar)
00151     {
00152       p -= scalar;
00153     }
00154 
00155     template<typename T1, typename T2> inline
00156     typename boost::enable_if_c<boost::is_array<T1>::value>::type
00157     minusscalar (T1 &p, const T2 &scalar)
00158     {
00159       typedef typename boost::remove_all_extents<T1>::type type;
00160       static const uint32_t count = sizeof (T1) / sizeof (type);
00161       for (int i = 0; i < count; ++i)
00162         p[i] -= scalar;
00163     }
00164 
00165     template<typename T1, typename T2> inline
00166     typename boost::disable_if_c<boost::is_array<T1>::value>::type
00167     mulscalar (T1 &p, const T2 &scalar)
00168     {
00169       p *= scalar;
00170     }
00171 
00172     template<typename T1, typename T2> inline
00173     typename boost::enable_if_c<boost::is_array<T1>::value>::type
00174     mulscalar (T1 &p, const T2 &scalar)
00175     {
00176       typedef typename boost::remove_all_extents<T1>::type type;
00177       static const uint32_t count = sizeof (T1) / sizeof (type);
00178       for (int i = 0; i < count; ++i)
00179         p[i] *= scalar;
00180     }
00181 
00182     template<typename T1, typename T2> inline
00183     typename boost::disable_if_c<boost::is_array<T1>::value>::type
00184     divscalar (T1 &p, const T2 &scalar)
00185     {
00186       p /= scalar;
00187     }
00188 
00189     template<typename T1, typename T2> inline
00190     typename boost::enable_if_c<boost::is_array<T1>::value>::type
00191     divscalar (T1 &p, const T2 &scalar)
00192     {
00193       typedef typename boost::remove_all_extents<T1>::type type;
00194       static const uint32_t count = sizeof (T1) / sizeof (type);
00195       for (int i = 0; i < count; ++i)
00196         p[i] /= scalar;
00197     }
00198   }
00199 }
00200 
00201 // Point operators
00202 #define PCL_PLUSEQ_POINT_TAG(r, data, elem)                \
00203   pcl::traits::plus (lhs.BOOST_PP_TUPLE_ELEM(3, 1, elem),  \
00204                      rhs.BOOST_PP_TUPLE_ELEM(3, 1, elem)); \
00205   /***/
00206 
00207 #define PCL_PLUSEQSC_POINT_TAG(r, data, elem)                 \
00208   pcl::traits::plusscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \
00209                            scalar);                           \
00210   /***/
00211    //p.BOOST_PP_TUPLE_ELEM(3, 1, elem) += scalar;  \
00212 
00213 #define PCL_MINUSEQ_POINT_TAG(r, data, elem)                \
00214   pcl::traits::minus (lhs.BOOST_PP_TUPLE_ELEM(3, 1, elem),  \
00215                       rhs.BOOST_PP_TUPLE_ELEM(3, 1, elem)); \
00216   /***/
00217 
00218 #define PCL_MINUSEQSC_POINT_TAG(r, data, elem)                 \
00219   pcl::traits::minusscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \
00220                             scalar);                           \
00221   /***/
00222    //p.BOOST_PP_TUPLE_ELEM(3, 1, elem) -= scalar;   \
00223 
00224 #define PCL_MULEQSC_POINT_TAG(r, data, elem)                 \
00225   pcl::traits::mulscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \
00226                             scalar);                         \
00227   /***/
00228 
00229 #define PCL_DIVEQSC_POINT_TAG(r, data, elem)   \
00230   pcl::traits::divscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \
00231                             scalar);                         \
00232   /***/
00233 
00234 // Construct type traits given full sequence of (type, name, tag) triples
00235 //  BOOST_MPL_ASSERT_MSG(boost::is_pod<name>::value,
00236 //                       REGISTERED_POINT_TYPE_MUST_BE_PLAIN_OLD_DATA, (name));
00237 #define POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, seq)                           \
00238   namespace pcl                                                                  \
00239   {                                                                              \
00240     namespace fields                                                             \
00241     {                                                                            \
00242       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_TAG, name, seq)           \
00243     }                                                                            \
00244     namespace traits                                                             \
00245     {                                                                            \
00246       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_NAME, name, seq)          \
00247       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_OFFSET, name, seq)        \
00248       BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_DATATYPE, name, seq)      \
00249       POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, POINT_CLOUD_EXTRACT_TAGS(seq)) \
00250     }                                                                            \
00251     namespace common                                           \
00252     {                                                          \
00253       inline const name&                                       \
00254       operator+= (name& lhs, const name& rhs)                  \
00255       {                                                        \
00256         BOOST_PP_SEQ_FOR_EACH(PCL_PLUSEQ_POINT_TAG, _, seq)    \
00257         return (lhs);                                          \
00258       }                                                        \
00259       inline const name&                                       \
00260       operator+= (name& p, const float& scalar)                \
00261       {                                                        \
00262         BOOST_PP_SEQ_FOR_EACH(PCL_PLUSEQSC_POINT_TAG, _, seq)  \
00263         return (p);                                            \
00264       }                                                        \
00265       inline const name operator+ (const name& lhs, const name& rhs)   \
00266       { name result = lhs; result += rhs; return (result); }           \
00267       inline const name operator+ (const float& scalar, const name& p) \
00268       { name result = p; result += scalar; return (result); }          \
00269       inline const name operator+ (const name& p, const float& scalar) \
00270       { name result = p; result += scalar; return (result); }          \
00271       inline const name&                                       \
00272       operator-= (name& lhs, const name& rhs)                  \
00273       {                                                        \
00274         BOOST_PP_SEQ_FOR_EACH(PCL_MINUSEQ_POINT_TAG, _, seq)   \
00275         return (lhs);                                          \
00276       }                                                        \
00277       inline const name&                                       \
00278       operator-= (name& p, const float& scalar)                \
00279       {                                                        \
00280         BOOST_PP_SEQ_FOR_EACH(PCL_MINUSEQSC_POINT_TAG, _, seq) \
00281         return (p);                                            \
00282       }                                                        \
00283       inline const name operator- (const name& lhs, const name& rhs)   \
00284       { name result = lhs; result -= rhs; return (result); }           \
00285       inline const name operator- (const float& scalar, const name& p) \
00286       { name result = p; result -= scalar; return (result); }          \
00287       inline const name operator- (const name& p, const float& scalar) \
00288       { name result = p; result -= scalar; return (result); }          \
00289       inline const name&                                       \
00290       operator*= (name& p, const float& scalar)                \
00291       {                                                        \
00292         BOOST_PP_SEQ_FOR_EACH(PCL_MULEQSC_POINT_TAG, _, seq)   \
00293         return (p);                                            \
00294       }                                                        \
00295       inline const name operator* (const float& scalar, const name& p) \
00296       { name result = p; result *= scalar; return (result); }          \
00297       inline const name operator* (const name& p, const float& scalar) \
00298       { name result = p; result *= scalar; return (result); }          \
00299       inline const name&                                       \
00300       operator/= (name& p, const float& scalar)                \
00301       {                                                        \
00302         BOOST_PP_SEQ_FOR_EACH(PCL_DIVEQSC_POINT_TAG, _, seq)   \
00303         return (p);                                            \
00304       }                                                        \
00305       inline const name operator/ (const float& scalar, const name& p) \
00306       { name result = p; result /= scalar; return (result); }          \
00307       inline const name operator/ (const name& p, const float& scalar) \
00308       { name result = p; result /= scalar; return (result); }          \
00309     }                                                          \
00310   }                                                            \
00311   /***/
00312 
00313 #define POINT_CLOUD_REGISTER_FIELD_TAG(r, name, elem)   \
00314   struct BOOST_PP_TUPLE_ELEM(3, 2, elem);               \
00315   /***/
00316 
00317 #define POINT_CLOUD_REGISTER_FIELD_NAME(r, point, elem)                 \
00318   template<int dummy>                                                   \
00319   struct name<point, pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem), dummy> \
00320   {                                                                     \
00321     static const char value[];                                          \
00322   };                                                                    \
00323                                                                         \
00324   template<int dummy>                                                   \
00325   const char name<point,                                                \
00326                   pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem),         \
00327                   dummy>::value[] =                                     \
00328     BOOST_PP_STRINGIZE(BOOST_PP_TUPLE_ELEM(3, 2, elem));                \
00329   /***/
00330 
00331 #define POINT_CLOUD_REGISTER_FIELD_OFFSET(r, name, elem)                \
00332   template<> struct offset<name, pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem)> \
00333   {                                                                     \
00334     static const size_t value = offsetof(name, BOOST_PP_TUPLE_ELEM(3, 1, elem)); \
00335   };                                                                    \
00336   /***/
00337 
00338 // \note: the mpl::identity weirdness is to support array types without requiring the
00339 // user to wrap them. The basic problem is:
00340 // typedef float[81] type; // SYNTAX ERROR!
00341 // typedef float type[81]; // OK, can now use "type" as a synonym for float[81]
00342 #define POINT_CLOUD_REGISTER_FIELD_DATATYPE(r, name, elem)              \
00343   template<> struct datatype<name, pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem)> \
00344   {                                                                     \
00345     typedef boost::mpl::identity<BOOST_PP_TUPLE_ELEM(3, 0, elem)>::type type; \
00346     typedef decomposeArray<type> decomposed;                            \
00347     static const uint8_t value = asEnum<decomposed::type>::value;       \
00348     static const uint32_t size = decomposed::value;                     \
00349   };                                                                    \
00350   /***/
00351 
00352 #define POINT_CLOUD_TAG_OP(s, data, elem) pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem)
00353 
00354 #define POINT_CLOUD_EXTRACT_TAGS(seq) BOOST_PP_SEQ_TRANSFORM(POINT_CLOUD_TAG_OP, _, seq)
00355 
00356 #define POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, seq)        \
00357   template<> struct fieldList<name>                             \
00358   {                                                             \
00359     typedef boost::mpl::vector<BOOST_PP_SEQ_ENUM(seq)> type;    \
00360   };                                                            \
00361   /***/
00362 
00363 #if defined _MSC_VER
00364   #pragma warning (pop)
00365 #endif
00366 
00367 #endif  //#ifndef PCL_REGISTER_POINT_STRUCT_H_


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