Scalar.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2003-2009 Erwin Coumans  http://bullet.googlecode.com
00003 
00004 This software is provided 'as-is', without any express or implied warranty.
00005 In no event will the authors be held liable for any damages arising from the use of this software.
00006 Permission is granted to anyone to use this software for any purpose, 
00007 including commercial applications, and to alter it and redistribute it freely, 
00008 subject to the following restrictions:
00009 
00010 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
00011 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00012 3. This notice may not be removed or altered from any source distribution.
00013 */
00014 
00015 
00016 
00017 #ifndef TF_SCALAR_H
00018 #define TF_SCALAR_H
00019 
00020 #ifdef TF_MANAGED_CODE
00021 //Aligned data types not supported in managed code
00022 #pragma unmanaged
00023 #endif
00024 
00025 
00026 #include <math.h>
00027 #include <stdlib.h>//size_t for MSVC 6.0
00028 #include <cstdlib>
00029 #include <cfloat>
00030 #include <float.h>
00031 
00032 #if defined(DEBUG) || defined (_DEBUG)
00033 #define TF_DEBUG
00034 #endif
00035 
00036 
00037 #ifdef _WIN32
00038 
00039                 #if defined(__MINGW32__) || defined(__CYGWIN__) || (defined (_MSC_VER) && _MSC_VER < 1300)
00040 
00041                         #define TFSIMD_FORCE_INLINE inline
00042                         #define ATTRIBUTE_ALIGNED16(a) a
00043                         #define ATTRIBUTE_ALIGNED64(a) a
00044                         #define ATTRIBUTE_ALIGNED128(a) a
00045                 #else
00046                         //#define TF_HAS_ALIGNED_ALLOCATOR
00047                         #pragma warning(disable : 4324) // disable padding warning
00048 //                      #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning.
00049 //                      #pragma warning(disable:4996) //Turn off warnings about deprecated C routines
00050 //                      #pragma warning(disable:4786) // Disable the "debug name too long" warning
00051 
00052                         #define TFSIMD_FORCE_INLINE __forceinline
00053                         #define ATTRIBUTE_ALIGNED16(a) __declspec(align(16)) a
00054                         #define ATTRIBUTE_ALIGNED64(a) __declspec(align(64)) a
00055                         #define ATTRIBUTE_ALIGNED128(a) __declspec (align(128)) a
00056                 #ifdef _XBOX
00057                         #define TF_USE_VMX128
00058 
00059                         #include <ppcintrinsics.h>
00060                         #define TF_HAVE_NATIVE_FSEL
00061                         #define tfFsel(a,b,c) __fsel((a),(b),(c))
00062                 #else
00063 
00064 
00065                 #endif//_XBOX
00066 
00067                 #endif //__MINGW32__
00068 
00069                 #include <assert.h>
00070 #ifdef TF_DEBUG
00071                 #define tfAssert assert
00072 #else
00073                 #define tfAssert(x)
00074 #endif
00075                 //tfFullAssert is optional, slows down a lot
00076                 #define tfFullAssert(x)
00077 
00078                 #define tfLikely(_c)  _c
00079                 #define tfUnlikely(_c) _c
00080 
00081 #else
00082         
00083 #if defined     (__CELLOS_LV2__)
00084                 #define TFSIMD_FORCE_INLINE inline
00085                 #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16)))
00086                 #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64)))
00087                 #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128)))
00088                 #ifndef assert
00089                 #include <assert.h>
00090                 #endif
00091 #ifdef TF_DEBUG
00092                 #define tfAssert assert
00093 #else
00094                 #define tfAssert(x)
00095 #endif
00096                 //tfFullAssert is optional, slows down a lot
00097                 #define tfFullAssert(x)
00098 
00099                 #define tfLikely(_c)  _c
00100                 #define tfUnlikely(_c) _c
00101 
00102 #else
00103 
00104 #ifdef USE_LIBSPE2
00105 
00106                 #define TFSIMD_FORCE_INLINE __inline
00107                 #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16)))
00108                 #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64)))
00109                 #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128)))
00110                 #ifndef assert
00111                 #include <assert.h>
00112                 #endif
00113 #ifdef TF_DEBUG
00114                 #define tfAssert assert
00115 #else
00116                 #define tfAssert(x)
00117 #endif
00118                 //tfFullAssert is optional, slows down a lot
00119                 #define tfFullAssert(x)
00120 
00121 
00122                 #define tfLikely(_c)   __builtin_expect((_c), 1)
00123                 #define tfUnlikely(_c) __builtin_expect((_c), 0)
00124                 
00125 
00126 #else
00127         //non-windows systems
00128 
00129 
00130                 #define TFSIMD_FORCE_INLINE inline
00131 
00132 
00133 
00134 
00135                 #define ATTRIBUTE_ALIGNED16(a) a
00136                 #define ATTRIBUTE_ALIGNED64(a) a
00137                 #define ATTRIBUTE_ALIGNED128(a) a
00138                 #ifndef assert
00139                 #include <assert.h>
00140                 #endif
00141 
00142 #if defined(DEBUG) || defined (_DEBUG)
00143                 #define tfAssert assert
00144 #else
00145                 #define tfAssert(x)
00146 #endif
00147 
00148                 //tfFullAssert is optional, slows down a lot
00149                 #define tfFullAssert(x)
00150                 #define tfLikely(_c)  _c
00151                 #define tfUnlikely(_c) _c
00152 
00153 #endif // LIBSPE2
00154 
00155 #endif  //__CELLOS_LV2__
00156 #endif
00157 
00158 
00160 typedef double tfScalar;
00161 //this number could be bigger in double precision
00162 #define TF_LARGE_FLOAT 1e30
00163 
00164 
00165 
00166 #define TF_DECLARE_ALIGNED_ALLOCATOR() \
00167    TFSIMD_FORCE_INLINE void* operator new(size_t sizeInBytes)   { return tfAlignedAlloc(sizeInBytes,16); }   \
00168    TFSIMD_FORCE_INLINE void  operator delete(void* ptr)         { tfAlignedFree(ptr); }   \
00169    TFSIMD_FORCE_INLINE void* operator new(size_t, void* ptr)   { return ptr; }   \
00170    TFSIMD_FORCE_INLINE void  operator delete(void*, void*)      { }   \
00171    TFSIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes)   { return tfAlignedAlloc(sizeInBytes,16); }   \
00172    TFSIMD_FORCE_INLINE void  operator delete[](void* ptr)         { tfAlignedFree(ptr); }   \
00173    TFSIMD_FORCE_INLINE void* operator new[](size_t, void* ptr)   { return ptr; }   \
00174    TFSIMD_FORCE_INLINE void  operator delete[](void*, void*)      { }   \
00175 
00176 
00177 
00178                 
00179 TFSIMD_FORCE_INLINE tfScalar tfSqrt(tfScalar x) { return sqrt(x); }
00180 TFSIMD_FORCE_INLINE tfScalar tfFabs(tfScalar x) { return fabs(x); }
00181 TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x) { return cos(x); }
00182 TFSIMD_FORCE_INLINE tfScalar tfSin(tfScalar x) { return sin(x); }
00183 TFSIMD_FORCE_INLINE tfScalar tfTan(tfScalar x) { return tan(x); }
00184 TFSIMD_FORCE_INLINE tfScalar tfAcos(tfScalar x) { if (x<tfScalar(-1))   x=tfScalar(-1); if (x>tfScalar(1))      x=tfScalar(1); return acos(x); }
00185 TFSIMD_FORCE_INLINE tfScalar tfAsin(tfScalar x) { if (x<tfScalar(-1))   x=tfScalar(-1); if (x>tfScalar(1))      x=tfScalar(1); return asin(x); }
00186 TFSIMD_FORCE_INLINE tfScalar tfAtan(tfScalar x) { return atan(x); }
00187 TFSIMD_FORCE_INLINE tfScalar tfAtan2(tfScalar x, tfScalar y) { return atan2(x, y); }
00188 TFSIMD_FORCE_INLINE tfScalar tfExp(tfScalar x) { return exp(x); }
00189 TFSIMD_FORCE_INLINE tfScalar tfLog(tfScalar x) { return log(x); }
00190 TFSIMD_FORCE_INLINE tfScalar tfPow(tfScalar x,tfScalar y) { return pow(x,y); }
00191 TFSIMD_FORCE_INLINE tfScalar tfFmod(tfScalar x,tfScalar y) { return fmod(x,y); }
00192 
00193 
00194 #define TFSIMD_2_PI         tfScalar(6.283185307179586232)
00195 #define TFSIMD_PI           (TFSIMD_2_PI * tfScalar(0.5))
00196 #define TFSIMD_HALF_PI      (TFSIMD_2_PI * tfScalar(0.25))
00197 #define TFSIMD_RADS_PER_DEG (TFSIMD_2_PI / tfScalar(360.0))
00198 #define TFSIMD_DEGS_PER_RAD  (tfScalar(360.0) / TFSIMD_2_PI)
00199 #define TFSIMDSQRT12 tfScalar(0.7071067811865475244008443621048490)
00200 
00201 #define tfRecipSqrt(x) ((tfScalar)(tfScalar(1.0)/tfSqrt(tfScalar(x))))          /* reciprocal square root */
00202 
00203 
00204 #define TFSIMD_EPSILON      DBL_EPSILON
00205 #define TFSIMD_INFINITY     DBL_MAX
00206 
00207 TFSIMD_FORCE_INLINE tfScalar tfAtan2Fast(tfScalar y, tfScalar x) 
00208 {
00209         tfScalar coeff_1 = TFSIMD_PI / 4.0f;
00210         tfScalar coeff_2 = 3.0f * coeff_1;
00211         tfScalar abs_y = tfFabs(y);
00212         tfScalar angle;
00213         if (x >= 0.0f) {
00214                 tfScalar r = (x - abs_y) / (x + abs_y);
00215                 angle = coeff_1 - coeff_1 * r;
00216         } else {
00217                 tfScalar r = (x + abs_y) / (abs_y - x);
00218                 angle = coeff_2 - coeff_1 * r;
00219         }
00220         return (y < 0.0f) ? -angle : angle;
00221 }
00222 
00223 TFSIMD_FORCE_INLINE bool      tfFuzzyZero(tfScalar x) { return tfFabs(x) < TFSIMD_EPSILON; }
00224 
00225 TFSIMD_FORCE_INLINE bool        tfEqual(tfScalar a, tfScalar eps) {
00226         return (((a) <= eps) && !((a) < -eps));
00227 }
00228 TFSIMD_FORCE_INLINE bool        tfGreaterEqual (tfScalar a, tfScalar eps) {
00229         return (!((a) <= eps));
00230 }
00231 
00232 
00233 TFSIMD_FORCE_INLINE int       tfIsNegative(tfScalar x) {
00234     return x < tfScalar(0.0) ? 1 : 0;
00235 }
00236 
00237 TFSIMD_FORCE_INLINE tfScalar tfRadians(tfScalar x) { return x * TFSIMD_RADS_PER_DEG; }
00238 TFSIMD_FORCE_INLINE tfScalar tfDegrees(tfScalar x) { return x * TFSIMD_DEGS_PER_RAD; }
00239 
00240 #define TF_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name
00241 
00242 #ifndef tfFsel
00243 TFSIMD_FORCE_INLINE tfScalar tfFsel(tfScalar a, tfScalar b, tfScalar c)
00244 {
00245         return a >= 0 ? b : c;
00246 }
00247 #endif
00248 #define tfFsels(a,b,c) (tfScalar)tfFsel(a,b,c)
00249 
00250 
00251 TFSIMD_FORCE_INLINE bool tfMachineIsLittleEndian()
00252 {
00253    long int i = 1;
00254    const char *p = (const char *) &i;
00255    if (p[0] == 1)  // Lowest address contains the least significant byte
00256            return true;
00257    else
00258            return false;
00259 }
00260 
00261 
00262 
00265 TFSIMD_FORCE_INLINE unsigned tfSelect(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) 
00266 {
00267     // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero
00268     // Rely on positive value or'ed with its negative having sign bit on
00269     // and zero value or'ed with its negative (which is still zero) having sign bit off 
00270     // Use arithmetic shift right, shifting the sign bit through all 32 bits
00271     unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
00272     unsigned testEqz = ~testNz;
00273     return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); 
00274 }
00275 TFSIMD_FORCE_INLINE int tfSelect(unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero)
00276 {
00277     unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
00278     unsigned testEqz = ~testNz; 
00279     return static_cast<int>((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz));
00280 }
00281 TFSIMD_FORCE_INLINE float tfSelect(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero)
00282 {
00283 #ifdef TF_HAVE_NATIVE_FSEL
00284     return (float)tfFsel((tfScalar)condition - tfScalar(1.0f), valueIfConditionNonZero, valueIfConditionZero);
00285 #else
00286     return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; 
00287 #endif
00288 }
00289 
00290 template<typename T> TFSIMD_FORCE_INLINE void tfSwap(T& a, T& b)
00291 {
00292         T tmp = a;
00293         a = b;
00294         b = tmp;
00295 }
00296 
00297 
00298 //PCK: endian swapping functions
00299 TFSIMD_FORCE_INLINE unsigned tfSwapEndian(unsigned val)
00300 {
00301         return (((val & 0xff000000) >> 24) | ((val & 0x00ff0000) >> 8) | ((val & 0x0000ff00) << 8)  | ((val & 0x000000ff) << 24));
00302 }
00303 
00304 TFSIMD_FORCE_INLINE unsigned short tfSwapEndian(unsigned short val)
00305 {
00306         return static_cast<unsigned short>(((val & 0xff00) >> 8) | ((val & 0x00ff) << 8));
00307 }
00308 
00309 TFSIMD_FORCE_INLINE unsigned tfSwapEndian(int val)
00310 {
00311         return tfSwapEndian((unsigned)val);
00312 }
00313 
00314 TFSIMD_FORCE_INLINE unsigned short tfSwapEndian(short val)
00315 {
00316         return tfSwapEndian((unsigned short) val);
00317 }
00318 
00325 TFSIMD_FORCE_INLINE unsigned int  tfSwapEndianFloat(float d)
00326 {
00327     unsigned int a = 0;
00328     unsigned char *dst = (unsigned char *)&a;
00329     unsigned char *src = (unsigned char *)&d;
00330 
00331     dst[0] = src[3];
00332     dst[1] = src[2];
00333     dst[2] = src[1];
00334     dst[3] = src[0];
00335     return a;
00336 }
00337 
00338 // unswap using char pointers
00339 TFSIMD_FORCE_INLINE float tfUnswapEndianFloat(unsigned int a) 
00340 {
00341     float d = 0.0f;
00342     unsigned char *src = (unsigned char *)&a;
00343     unsigned char *dst = (unsigned char *)&d;
00344 
00345     dst[0] = src[3];
00346     dst[1] = src[2];
00347     dst[2] = src[1];
00348     dst[3] = src[0];
00349 
00350     return d;
00351 }
00352 
00353 
00354 // swap using char pointers
00355 TFSIMD_FORCE_INLINE void  tfSwapEndianDouble(double d, unsigned char* dst)
00356 {
00357     unsigned char *src = (unsigned char *)&d;
00358 
00359     dst[0] = src[7];
00360     dst[1] = src[6];
00361     dst[2] = src[5];
00362     dst[3] = src[4];
00363     dst[4] = src[3];
00364     dst[5] = src[2];
00365     dst[6] = src[1];
00366     dst[7] = src[0];
00367 
00368 }
00369 
00370 // unswap using char pointers
00371 TFSIMD_FORCE_INLINE double tfUnswapEndianDouble(const unsigned char *src) 
00372 {
00373     double d = 0.0;
00374     unsigned char *dst = (unsigned char *)&d;
00375 
00376     dst[0] = src[7];
00377     dst[1] = src[6];
00378     dst[2] = src[5];
00379     dst[3] = src[4];
00380     dst[4] = src[3];
00381     dst[5] = src[2];
00382     dst[6] = src[1];
00383     dst[7] = src[0];
00384 
00385         return d;
00386 }
00387 
00388 // returns normalized value in range [-TFSIMD_PI, TFSIMD_PI]
00389 TFSIMD_FORCE_INLINE tfScalar tfNormalizeAngle(tfScalar angleInRadians) 
00390 {
00391         angleInRadians = tfFmod(angleInRadians, TFSIMD_2_PI);
00392         if(angleInRadians < -TFSIMD_PI)
00393         {
00394                 return angleInRadians + TFSIMD_2_PI;
00395         }
00396         else if(angleInRadians > TFSIMD_PI)
00397         {
00398                 return angleInRadians - TFSIMD_2_PI;
00399         }
00400         else
00401         {
00402                 return angleInRadians;
00403         }
00404 }
00405 
00407 struct tfTypedObject
00408 {
00409         tfTypedObject(int objectType)
00410                 :m_objectType(objectType)
00411         {
00412         }
00413         int     m_objectType;
00414         inline int getObjectType() const
00415         {
00416                 return m_objectType;
00417         }
00418 };
00419 #endif //TFSIMD___SCALAR_H


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 18:45:32