pcl_macros.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 the copyright holder(s) 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 
00037 #ifndef PCL_MACROS_H_
00038 #define PCL_MACROS_H_
00039 
00040 #include <pcl/pcl_config.h>
00041 #include <boost/cstdint.hpp>
00042 #include <cstdlib>
00043 
00044 namespace pcl
00045 {
00046   using boost::uint8_t;
00047   using boost::int8_t;
00048   using boost::int16_t;
00049   using boost::uint16_t;
00050   using boost::int32_t;
00051   using boost::uint32_t;
00052   using boost::int64_t;
00053   using boost::uint64_t;
00054   using boost::int_fast16_t;
00055 }
00056 
00057 #if defined __INTEL_COMPILER
00058   #pragma warning disable 2196 2536 279
00059 #endif
00060 
00061 #if defined _MSC_VER
00062   // 4244 : conversion from 'type1' to 'type2', possible loss of data
00063   // 4661 : no suitable definition provided for explicit template instantiation reques
00064   // 4503 : decorated name length exceeded, name was truncated
00065   // 4146 : unary minus operator applied to unsigned type, result still unsigned
00066   #pragma warning (disable: 4018 4244 4267 4521 4251 4661 4305 4503 4146)
00067 #endif
00068 
00069 #include <iostream>
00070 #include <stdarg.h>
00071 #include <stdio.h>
00072 #define _USE_MATH_DEFINES
00073 #include <math.h>
00074 
00075 // MSCV doesn't have std::{isnan,isfinite}
00076 #if defined _WIN32 && defined _MSC_VER
00077 
00078 // If M_PI is not defined, then probably all of them are undefined
00079 #ifndef M_PI
00080 // Copied from math.h
00081 # define M_PI   3.14159265358979323846     // pi
00082 # define M_PI_2    1.57079632679489661923  // pi/2
00083 # define M_PI_4    0.78539816339744830962  // pi/4
00084 # define M_PIl   3.1415926535897932384626433832795029L  // pi
00085 # define M_PI_2l 1.5707963267948966192313216916397514L  // pi/2
00086 # define M_PI_4l 0.7853981633974483096156608458198757L  // pi/4
00087 #endif
00088 
00089 // Stupid. This should be removed when all the PCL dependencies have min/max fixed.
00090 #ifndef NOMINMAX
00091 # define NOMINMAX
00092 #endif
00093 
00094 # define pcl_isnan(x)    _isnan(x)
00095 # define pcl_isfinite(x) (_finite(x) != 0)
00096 # define pcl_isinf(x)    (_finite(x) == 0)
00097 
00098 # define __PRETTY_FUNCTION__ __FUNCTION__
00099 # define __func__ __FUNCTION__
00100 
00101 #elif ANDROID
00102 // Use the math.h macros
00103 # include <math.h>
00104 # define pcl_isnan(x)    isnan(x)
00105 # define pcl_isfinite(x) isfinite(x)
00106 # define pcl_isinf(x)    isinf(x)
00107 
00108 #elif _GLIBCXX_USE_C99_MATH
00109 // Are the C++ cmath functions enabled?
00110 # include <cmath>
00111 # define pcl_isnan(x)    std::isnan(x)
00112 # define pcl_isfinite(x) std::isfinite(x)
00113 # define pcl_isinf(x)    std::isinf(x)
00114 
00115 #elif __PATHCC__
00116 # include <cmath>
00117 # include <stdio.h>
00118 template <typename T> int
00119 pcl_isnan (T &val)
00120 {
00121   return (val != val);
00122 }
00123 //# define pcl_isnan(x)    std::isnan(x)
00124 # define pcl_isfinite(x) std::isfinite(x)
00125 # define pcl_isinf(x)    std::isinf(x)
00126 
00127 #else
00128 // Use the math.h macros
00129 # include <math.h>
00130 # define pcl_isnan(x)    isnan(x)
00131 # define pcl_isfinite(x) isfinite(x)
00132 # define pcl_isinf(x)    isinf(x)
00133 
00134 #endif
00135 
00136 #ifndef DEG2RAD
00137 #define DEG2RAD(x) ((x)*0.017453293)
00138 #endif
00139 
00140 #ifndef RAD2DEG
00141 #define RAD2DEG(x) ((x)*57.29578)
00142 #endif
00143 
00146 #define PCL_LINEAR_VERSION(major,minor,patch) ((major)<<16|(minor)<<8|(patch))
00147 
00152 __inline double
00153 pcl_round (double number)
00154 {
00155   return (number < 0.0 ? ceil (number - 0.5) : floor (number + 0.5));
00156 }
00157 __inline float
00158 pcl_round (float number)
00159 {
00160   return (number < 0.0f ? ceilf (number - 0.5f) : floorf (number + 0.5f));
00161 }
00162 
00163 #ifdef __GNUC__
00164 #define pcl_lrint(x) (lrint(static_cast<double> (x)))
00165 #define pcl_lrintf(x) (lrintf(static_cast<float> (x)))
00166 #else
00167 #define pcl_lrint(x) (static_cast<long int>(pcl_round(x)))
00168 #define pcl_lrintf(x) (static_cast<long int>(pcl_round(x)))
00169 #endif
00170 
00171 
00172 #ifdef _WIN32
00173 __inline float
00174 log2f (float x)
00175 {
00176   return (static_cast<float> (logf (x) * M_LOG2E));
00177 }
00178 #endif
00179 
00180 #ifdef WIN32
00181 #define pcl_sleep(x) Sleep(1000*(x))
00182 #else
00183 #define pcl_sleep(x) sleep(x)
00184 #endif
00185 
00186 #ifndef PVAR
00187   #define PVAR(s) \
00188     #s << " = " << (s) << std::flush
00189 #endif
00190 #ifndef PVARN
00191 #define PVARN(s) \
00192   #s << " = " << (s) << "\n"
00193 #endif
00194 #ifndef PVARC
00195 #define PVARC(s) \
00196   #s << " = " << (s) << ", " << std::flush
00197 #endif
00198 #ifndef PVARS
00199 #define PVARS(s) \
00200   #s << " = " << (s) << " " << std::flush
00201 #endif
00202 #ifndef PVARA
00203 #define PVARA(s) \
00204   #s << " = " << RAD2DEG(s) << "deg" << std::flush
00205 #endif
00206 #ifndef PVARAN
00207 #define PVARAN(s) \
00208   #s << " = " << RAD2DEG(s) << "deg\n"
00209 #endif
00210 #ifndef PVARAC
00211 #define PVARAC(s) \
00212   #s << " = " << RAD2DEG(s) << "deg, " << std::flush
00213 #endif
00214 #ifndef PVARAS
00215 #define PVARAS(s) \
00216   #s << " = " << RAD2DEG(s) << "deg " << std::flush
00217 #endif
00218 
00219 #define FIXED(s) \
00220   std::fixed << s << std::resetiosflags(std::ios_base::fixed)
00221 
00222 #ifndef ERASE_STRUCT
00223 #define ERASE_STRUCT(var) memset(&var, 0, sizeof(var))
00224 #endif
00225 
00226 #ifndef ERASE_ARRAY
00227 #define ERASE_ARRAY(var, size) memset(var, 0, size*sizeof(*var))
00228 #endif
00229 
00230 #ifndef SET_ARRAY
00231 #define SET_ARRAY(var, value, size) { for (int i = 0; i < static_cast<int> (size); ++i) var[i]=value; }
00232 #endif
00233 
00234 /* //This is copy/paste from http://gcc.gnu.org/wiki/Visibility */
00235 /* #if defined _WIN32 || defined __CYGWIN__ */
00236 /*   #ifdef BUILDING_DLL */
00237 /*     #ifdef __GNUC__ */
00238 /* #define DLL_PUBLIC __attribute__((dllexport)) */
00239 /*     #else */
00240 /* #define DLL_PUBLIC __declspec(dllexport) // Note: actually gcc seems to also supports this syntax. */
00241 /*     #endif */
00242 /*   #else */
00243 /*     #ifdef __GNUC__ */
00244 /* #define DLL_PUBLIC __attribute__((dllimport)) */
00245 /*     #else */
00246 /* #define DLL_PUBLIC __declspec(dllimport) // Note: actually gcc seems to also supports this syntax. */
00247 /*     #endif */
00248 /*   #endif */
00249 /*   #define DLL_LOCAL */
00250 /* #else */
00251 /*   #if __GNUC__ >= 4 */
00252 /* #define DLL_PUBLIC __attribute__ ((visibility("default"))) */
00253 /* #define DLL_LOCAL  __attribute__ ((visibility("hidden"))) */
00254 /*   #else */
00255 /*     #define DLL_PUBLIC */
00256 /*     #define DLL_LOCAL */
00257 /*   #endif */
00258 /* #endif */
00259 
00260 #ifndef PCL_EXTERN_C
00261     #ifdef __cplusplus
00262         #define PCL_EXTERN_C extern "C"
00263     #else
00264         #define PCL_EXTERN_C
00265     #endif
00266 #endif
00267 
00268 #if defined WIN32 || defined _WIN32 || defined WINCE || defined __MINGW32__
00269     #ifdef PCLAPI_EXPORTS
00270         #define PCL_EXPORTS __declspec(dllexport)
00271     #else
00272         #define PCL_EXPORTS
00273     #endif
00274 #else
00275     #define PCL_EXPORTS
00276 #endif
00277 
00278 #if defined WIN32 || defined _WIN32
00279     #define PCL_CDECL __cdecl
00280     #define PCL_STDCALL __stdcall
00281 #else
00282     #define PCL_CDECL
00283     #define PCL_STDCALL
00284 #endif
00285 
00286 #ifndef PCLAPI
00287     #define PCLAPI(rettype) PCL_EXTERN_C PCL_EXPORTS rettype PCL_CDECL
00288 #endif
00289 
00290 // Macro to deprecate old functions
00291 //
00292 // Usage:
00293 // don't use me any more
00294 // PCL_DEPRECATED(void OldFunc(int a, float b), "Use newFunc instead, this functions will be gone in the next major release");
00295 // use me instead
00296 // void NewFunc(int a, double b);
00297 
00298 //for clang cf. http://clang.llvm.org/docs/LanguageExtensions.html
00299 #ifndef __has_extension
00300   #define __has_extension(x) 0 // Compatibility with pre-3.0 compilers.
00301 #endif
00302 
00303 #if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) < PCL_LINEAR_VERSION(4,5,0) && ! defined(__clang__)) || defined(__INTEL_COMPILER)
00304 #define PCL_DEPRECATED(func, message) func __attribute__ ((deprecated))
00305 #endif
00306 
00307 // gcc supports this starting from 4.5 : http://gcc.gnu.org/bugzilla/show_bug.cgi?id=43666
00308 #if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) >= PCL_LINEAR_VERSION(4,5,0)) || (defined(__clang__) && __has_extension(attribute_deprecated_with_message))
00309 #define PCL_DEPRECATED(func, message) func __attribute__ ((deprecated(message)))
00310 #endif
00311 
00312 #ifdef _MSC_VER
00313 #define PCL_DEPRECATED(func, message) __declspec(deprecated(message)) func
00314 #endif
00315 
00316 #ifndef PCL_DEPRECATED
00317 #pragma message("WARNING: You need to implement PCL_DEPRECATED for this compiler")
00318 #define PCL_DEPRECATED(func) func
00319 #endif
00320 
00321 
00322 // Macro to deprecate old classes/structs
00323 //
00324 // Usage:
00325 // don't use me any more
00326 // class PCL_DEPRECATED_CLASS(OldClass, "Use newClass instead, this class will be gone in the next major release")
00327 // {
00328 //   public:
00329 //     OldClass() {}
00330 // };
00331 // use me instead
00332 // class NewFunc
00333 // {
00334 //   public:
00335 //     NewClass() {}
00336 // };
00337 
00338 #if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) < PCL_LINEAR_VERSION(4,5,0) && ! defined(__clang__)) || defined(__INTEL_COMPILER)
00339 #define PCL_DEPRECATED_CLASS(func, message) __attribute__ ((deprecated)) func
00340 #endif
00341 
00342 // gcc supports this starting from 4.5 : http://gcc.gnu.org/bugzilla/show_bug.cgi?id=43666
00343 #if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) >= PCL_LINEAR_VERSION(4,5,0)) || (defined(__clang__) && __has_extension(attribute_deprecated_with_message))
00344 #define PCL_DEPRECATED_CLASS(func, message) __attribute__ ((deprecated(message))) func
00345 #endif
00346 
00347 #ifdef _MSC_VER
00348 #define PCL_DEPRECATED_CLASS(func, message) __declspec(deprecated(message)) func
00349 #endif
00350 
00351 #ifndef PCL_DEPRECATED_CLASS
00352 #pragma message("WARNING: You need to implement PCL_DEPRECATED_CLASS for this compiler")
00353 #define PCL_DEPRECATED_CLASS(func) func
00354 #endif
00355 
00356 #if defined (__GNUC__) || defined (__PGI) || defined (__IBMCPP__) || defined (__SUNPRO_CC)
00357   #define PCL_ALIGN(alignment) __attribute__((aligned(alignment)))
00358 #elif defined (_MSC_VER)
00359   #define PCL_ALIGN(alignment) __declspec(align(alignment))
00360 #else
00361   #error Alignment not supported on your platform
00362 #endif
00363 
00364 #if defined(__GLIBC__) && PCL_LINEAR_VERSION(__GLIBC__,__GLIBC_MINOR__,0)>PCL_LINEAR_VERSION(2,8,0)
00365   #define GLIBC_MALLOC_ALIGNED 1
00366 #else
00367   #define GLIBC_MALLOC_ALIGNED 0
00368 #endif
00369 
00370 #if defined(__FreeBSD__) && !defined(__arm__) && !defined(__mips__)
00371   #define FREEBSD_MALLOC_ALIGNED 1
00372 #else
00373   #define FREEBSD_MALLOC_ALIGNED 0
00374 #endif
00375 
00376 #if defined(__APPLE__) || defined(_WIN64) || GLIBC_MALLOC_ALIGNED || FREEBSD_MALLOC_ALIGNED
00377   #define MALLOC_ALIGNED 1
00378 #else
00379   #define MALLOC_ALIGNED 0
00380 #endif
00381 
00382 inline void*
00383 aligned_malloc (size_t size)
00384 {
00385   void *ptr;
00386 #if   defined (MALLOC_ALIGNED)
00387   ptr = std::malloc (size);
00388 #elif defined (HAVE_POSIX_MEMALIGN)
00389   if (posix_memalign (&ptr, 16, size))
00390     ptr = 0;
00391 #elif defined (HAVE_MM_MALLOC)
00392   ptr = _mm_malloc (size, 16);
00393 #elif defined (_MSC_VER)
00394   ptr = _aligned_malloc (size, 16);
00395 #else
00396   #error aligned_malloc not supported on your platform
00397   ptr = 0;
00398 #endif
00399   return (ptr);
00400 }
00401 
00402 inline void
00403 aligned_free (void* ptr)
00404 {
00405 #if   defined (MALLOC_ALIGNED) || defined (HAVE_POSIX_MEMALIGN)
00406   std::free (ptr);
00407 #elif defined (HAVE_MM_MALLOC)
00408   ptr = _mm_free (ptr);
00409 #elif defined (_MSC_VER)
00410   _aligned_free (ptr);
00411 #else
00412   #error aligned_free not supported on your platform
00413 #endif
00414 }
00415 
00416 #endif  //#ifndef PCL_MACROS_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:28:09