00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_POINT_TRAITS_H_
00040 #define PCL_POINT_TRAITS_H_
00041
00042 #ifdef __GNUC__
00043 #pragma GCC system_header
00044 #endif
00045
00046 #include "pcl/pcl_macros.h"
00047
00048 #include <pcl/PCLPointField.h>
00049 #include <boost/type_traits/remove_all_extents.hpp>
00050 #include <boost/type_traits/is_same.hpp>
00051 #include <boost/mpl/assert.hpp>
00052 #if PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) == PCL_LINEAR_VERSION(4,4,3)
00053 #include <boost/mpl/bool.hpp>
00054 #endif
00055
00056 namespace pcl
00057 {
00058
00059 namespace fields
00060 {
00061
00062 }
00063
00064 namespace traits
00065 {
00066
00067 template<typename T> struct asEnum {};
00068 template<> struct asEnum<int8_t> { static const uint8_t value = pcl::PCLPointField::INT8; };
00069 template<> struct asEnum<uint8_t> { static const uint8_t value = pcl::PCLPointField::UINT8; };
00070 template<> struct asEnum<int16_t> { static const uint8_t value = pcl::PCLPointField::INT16; };
00071 template<> struct asEnum<uint16_t> { static const uint8_t value = pcl::PCLPointField::UINT16; };
00072 template<> struct asEnum<int32_t> { static const uint8_t value = pcl::PCLPointField::INT32; };
00073 template<> struct asEnum<uint32_t> { static const uint8_t value = pcl::PCLPointField::UINT32; };
00074 template<> struct asEnum<float> { static const uint8_t value = pcl::PCLPointField::FLOAT32; };
00075 template<> struct asEnum<double> { static const uint8_t value = pcl::PCLPointField::FLOAT64; };
00076
00077
00078 template<int> struct asType {};
00079 template<> struct asType<pcl::PCLPointField::INT8> { typedef int8_t type; };
00080 template<> struct asType<pcl::PCLPointField::UINT8> { typedef uint8_t type; };
00081 template<> struct asType<pcl::PCLPointField::INT16> { typedef int16_t type; };
00082 template<> struct asType<pcl::PCLPointField::UINT16> { typedef uint16_t type; };
00083 template<> struct asType<pcl::PCLPointField::INT32> { typedef int32_t type; };
00084 template<> struct asType<pcl::PCLPointField::UINT32> { typedef uint32_t type; };
00085 template<> struct asType<pcl::PCLPointField::FLOAT32> { typedef float type; };
00086 template<> struct asType<pcl::PCLPointField::FLOAT64> { typedef double type; };
00087
00088
00089
00090 template<typename T> struct decomposeArray
00091 {
00092 typedef typename boost::remove_all_extents<T>::type type;
00093 static const uint32_t value = sizeof (T) / sizeof (type);
00094 };
00095
00096
00097 template<typename PointT>
00098 struct POD
00099 {
00100 typedef PointT type;
00101 };
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113 template<class PointT, typename Tag, int dummy = 0>
00114 struct name : name<typename POD<PointT>::type, Tag, dummy>
00115 {
00116
00117
00118
00119
00120 BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00121 POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00122 };
00123
00124
00125 template<class PointT, typename Tag>
00126 struct offset : offset<typename POD<PointT>::type, Tag>
00127 {
00128
00129
00130
00131
00132 BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00133 POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00134 };
00135
00136
00137 template<class PointT, typename Tag>
00138 struct datatype : datatype<typename POD<PointT>::type, Tag>
00139 {
00140
00141
00142
00143
00144
00145
00146 BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00147 POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00148 };
00149
00150
00151 template<typename PointT>
00152 struct fieldList : fieldList<typename POD<PointT>::type>
00153 {
00154
00155
00156
00157
00158 BOOST_MPL_ASSERT_MSG((!boost::is_same<PointT, typename POD<PointT>::type>::value),
00159 POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&));
00160 };
00161 #if PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) == PCL_LINEAR_VERSION(4,4,3)
00162
00163
00164
00165
00166
00167
00168
00169
00170 BOOST_MPL_ASSERT_MSG((!bool (boost::mpl::bool_<false>::value)), WTF_GCC443, (bool));
00171 #endif
00172 }
00173
00174
00175
00176 template<typename PointT, typename Tag>
00177 struct FieldMatches
00178 {
00179 bool operator() (const pcl::PCLPointField& field)
00180 {
00181 return (field.name == traits::name<PointT, Tag>::value &&
00182 field.datatype == traits::datatype<PointT, Tag>::value &&
00183 (field.count == traits::datatype<PointT, Tag>::size ||
00184 field.count == 0 && traits::datatype<PointT, Tag>::size == 1 ));
00185 }
00186 };
00187
00189 template <typename PointInT, typename OutT>
00190 struct CopyIfFieldExists
00191 {
00192 typedef typename traits::POD<PointInT>::type Pod;
00193
00200 CopyIfFieldExists (const PointInT &pt,
00201 const std::string &field,
00202 bool &exists,
00203 OutT &value)
00204 : pt_ (reinterpret_cast<const Pod&>(pt)), name_ (field), exists_ (exists), value_ (value)
00205 {
00206 exists_ = false;
00207 }
00208
00214 CopyIfFieldExists (const PointInT &pt,
00215 const std::string &field,
00216 OutT &value)
00217 : pt_ (reinterpret_cast<const Pod&>(pt)), name_ (field), exists_ (exists_tmp_), value_ (value)
00218 {
00219 }
00220
00222 template <typename Key> inline void
00223 operator() ()
00224 {
00225 if (name_ == pcl::traits::name<PointInT, Key>::value)
00226 {
00227 exists_ = true;
00228 typedef typename pcl::traits::datatype<PointInT, Key>::type T;
00229 const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&pt_) + pcl::traits::offset<PointInT, Key>::value;
00230 value_ = static_cast<OutT> (*reinterpret_cast<const T*>(data_ptr));
00231 }
00232 }
00233
00234 private:
00235 const Pod &pt_;
00236 const std::string &name_;
00237 bool &exists_;
00238
00239 bool exists_tmp_;
00240 OutT &value_;
00241 };
00242
00244 template <typename PointOutT, typename InT>
00245 struct SetIfFieldExists
00246 {
00247 typedef typename traits::POD<PointOutT>::type Pod;
00248
00254 SetIfFieldExists (PointOutT &pt,
00255 const std::string &field,
00256 const InT &value)
00257 : pt_ (reinterpret_cast<Pod&>(pt)), name_ (field), value_ (value)
00258 {
00259 }
00260
00262 template <typename Key> inline void
00263 operator() ()
00264 {
00265 if (name_ == pcl::traits::name<PointOutT, Key>::value)
00266 {
00267 typedef typename pcl::traits::datatype<PointOutT, Key>::type T;
00268 uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&pt_) + pcl::traits::offset<PointOutT, Key>::value;
00269 *reinterpret_cast<T*>(data_ptr) = static_cast<T> (value_);
00270 }
00271 }
00272
00273 private:
00274 Pod &pt_;
00275 const std::string &name_;
00276 const InT &value_;
00277 };
00278
00284 template <typename PointT, typename ValT> inline void
00285 setFieldValue (PointT &pt, size_t field_offset, const ValT &value)
00286 {
00287 uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&pt) + field_offset;
00288 *reinterpret_cast<ValT*>(data_ptr) = value;
00289 }
00290
00296 template <typename PointT, typename ValT> inline void
00297 getFieldValue (const PointT &pt, size_t field_offset, ValT &value)
00298 {
00299 const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&pt) + field_offset;
00300 value = *reinterpret_cast<const ValT*>(data_ptr);
00301 }
00302 }
00303
00304 #endif //#ifndef PCL_POINT_TRAITS_H_