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 TF2_SCALAR_H
00018 #define TF2_SCALAR_H
00019 
00020 #ifdef TF2_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 TF2_DEBUG
00034 #endif
00035 
00036 
00037 #ifdef _WIN32
00038 
00039                 #if defined(__MINGW32__) || defined(__CYGWIN__) || (defined (_MSC_VER) && _MSC_VER < 1300)
00040 
00041                         #define TF2SIMD_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 TF2_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 TF2SIMD_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 TF2_USE_VMX128
00058 
00059                         #include <ppcintrinsics.h>
00060                         #define TF2_HAVE_NATIVE_FSEL
00061                         #define tf2Fsel(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 TF2_DEBUG
00071                 #define tf2Assert assert
00072 #else
00073                 #define tf2Assert(x)
00074 #endif
00075                 //tf2FullAssert is optional, slows down a lot
00076                 #define tf2FullAssert(x)
00077 
00078                 #define tf2Likely(_c)  _c
00079                 #define tf2Unlikely(_c) _c
00080 
00081 #else
00082         
00083 #if defined     (__CELLOS_LV2__)
00084                 #define TF2SIMD_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 TF2_DEBUG
00092                 #define tf2Assert assert
00093 #else
00094                 #define tf2Assert(x)
00095 #endif
00096                 //tf2FullAssert is optional, slows down a lot
00097                 #define tf2FullAssert(x)
00098 
00099                 #define tf2Likely(_c)  _c
00100                 #define tf2Unlikely(_c) _c
00101 
00102 #else
00103 
00104 #ifdef USE_LIBSPE2
00105 
00106                 #define TF2SIMD_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 TF2_DEBUG
00114                 #define tf2Assert assert
00115 #else
00116                 #define tf2Assert(x)
00117 #endif
00118                 //tf2FullAssert is optional, slows down a lot
00119                 #define tf2FullAssert(x)
00120 
00121 
00122                 #define tf2Likely(_c)   __builtin_expect((_c), 1)
00123                 #define tf2Unlikely(_c) __builtin_expect((_c), 0)
00124                 
00125 
00126 #else
00127         //non-windows systems
00128 
00129                 #define TF2SIMD_FORCE_INLINE inline
00130 
00131 
00132 
00133 
00134                 #define ATTRIBUTE_ALIGNED16(a) a
00135                 #define ATTRIBUTE_ALIGNED64(a) a
00136                 #define ATTRIBUTE_ALIGNED128(a) a
00137                 #ifndef assert
00138                 #include <assert.h>
00139                 #endif
00140 
00141 #if defined(DEBUG) || defined (_DEBUG)
00142                 #define tf2Assert assert
00143 #else
00144                 #define tf2Assert(x)
00145 #endif
00146 
00147                 //tf2FullAssert is optional, slows down a lot
00148                 #define tf2FullAssert(x)
00149                 #define tf2Likely(_c)  _c
00150                 #define tf2Unlikely(_c) _c
00151 
00152 #endif // LIBSPE2
00153 
00154 #endif  //__CELLOS_LV2__
00155 #endif
00156 
00157 
00159 typedef double tf2Scalar;
00160 //this number could be bigger in double precision
00161 #define TF2_LARGE_FLOAT 1e30
00162 
00163 
00164 #define TF2_DECLARE_ALIGNED_ALLOCATOR() \
00165    TF2SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes)   { return tf2AlignedAlloc(sizeInBytes,16); }   \
00166    TF2SIMD_FORCE_INLINE void  operator delete(void* ptr)         { tf2AlignedFree(ptr); }   \
00167    TF2SIMD_FORCE_INLINE void* operator new(size_t, void* ptr)   { return ptr; }   \
00168    TF2SIMD_FORCE_INLINE void  operator delete(void*, void*)      { }   \
00169    TF2SIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes)   { return tf2AlignedAlloc(sizeInBytes,16); }   \
00170    TF2SIMD_FORCE_INLINE void  operator delete[](void* ptr)         { tf2AlignedFree(ptr); }   \
00171    TF2SIMD_FORCE_INLINE void* operator new[](size_t, void* ptr)   { return ptr; }   \
00172    TF2SIMD_FORCE_INLINE void  operator delete[](void*, void*)      { }   \
00173 
00174 
00175 
00176                 
00177 TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x) { return sqrt(x); }
00178 TF2SIMD_FORCE_INLINE tf2Scalar tf2Fabs(tf2Scalar x) { return fabs(x); }
00179 TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x) { return cos(x); }
00180 TF2SIMD_FORCE_INLINE tf2Scalar tf2Sin(tf2Scalar x) { return sin(x); }
00181 TF2SIMD_FORCE_INLINE tf2Scalar tf2Tan(tf2Scalar x) { return tan(x); }
00182 TF2SIMD_FORCE_INLINE tf2Scalar tf2Acos(tf2Scalar x) { if (x<tf2Scalar(-1))      x=tf2Scalar(-1); if (x>tf2Scalar(1))    x=tf2Scalar(1); return acos(x); }
00183 TF2SIMD_FORCE_INLINE tf2Scalar tf2Asin(tf2Scalar x) { if (x<tf2Scalar(-1))      x=tf2Scalar(-1); if (x>tf2Scalar(1))    x=tf2Scalar(1); return asin(x); }
00184 TF2SIMD_FORCE_INLINE tf2Scalar tf2Atan(tf2Scalar x) { return atan(x); }
00185 TF2SIMD_FORCE_INLINE tf2Scalar tf2Atan2(tf2Scalar x, tf2Scalar y) { return atan2(x, y); }
00186 TF2SIMD_FORCE_INLINE tf2Scalar tf2Exp(tf2Scalar x) { return exp(x); }
00187 TF2SIMD_FORCE_INLINE tf2Scalar tf2Log(tf2Scalar x) { return log(x); }
00188 TF2SIMD_FORCE_INLINE tf2Scalar tf2Pow(tf2Scalar x,tf2Scalar y) { return pow(x,y); }
00189 TF2SIMD_FORCE_INLINE tf2Scalar tf2Fmod(tf2Scalar x,tf2Scalar y) { return fmod(x,y); }
00190 
00191 
00192 #define TF2SIMD_2_PI         tf2Scalar(6.283185307179586232)
00193 #define TF2SIMD_PI           (TF2SIMD_2_PI * tf2Scalar(0.5))
00194 #define TF2SIMD_HALF_PI      (TF2SIMD_2_PI * tf2Scalar(0.25))
00195 #define TF2SIMD_RADS_PER_DEG (TF2SIMD_2_PI / tf2Scalar(360.0))
00196 #define TF2SIMD_DEGS_PER_RAD  (tf2Scalar(360.0) / TF2SIMD_2_PI)
00197 #define TF2SIMDSQRT12 tf2Scalar(0.7071067811865475244008443621048490)
00198 
00199 #define tf2RecipSqrt(x) ((tf2Scalar)(tf2Scalar(1.0)/tf2Sqrt(tf2Scalar(x))))             /* reciprocal square root */
00200 
00201 
00202 #define TF2SIMD_EPSILON      DBL_EPSILON
00203 #define TF2SIMD_INFINITY     DBL_MAX
00204 
00205 TF2SIMD_FORCE_INLINE tf2Scalar tf2Atan2Fast(tf2Scalar y, tf2Scalar x) 
00206 {
00207         tf2Scalar coeff_1 = TF2SIMD_PI / 4.0f;
00208         tf2Scalar coeff_2 = 3.0f * coeff_1;
00209         tf2Scalar abs_y = tf2Fabs(y);
00210         tf2Scalar angle;
00211         if (x >= 0.0f) {
00212                 tf2Scalar r = (x - abs_y) / (x + abs_y);
00213                 angle = coeff_1 - coeff_1 * r;
00214         } else {
00215                 tf2Scalar r = (x + abs_y) / (abs_y - x);
00216                 angle = coeff_2 - coeff_1 * r;
00217         }
00218         return (y < 0.0f) ? -angle : angle;
00219 }
00220 
00221 TF2SIMD_FORCE_INLINE bool      tf2FuzzyZero(tf2Scalar x) { return tf2Fabs(x) < TF2SIMD_EPSILON; }
00222 
00223 TF2SIMD_FORCE_INLINE bool       tf2Equal(tf2Scalar a, tf2Scalar eps) {
00224         return (((a) <= eps) && !((a) < -eps));
00225 }
00226 TF2SIMD_FORCE_INLINE bool       tf2GreaterEqual (tf2Scalar a, tf2Scalar eps) {
00227         return (!((a) <= eps));
00228 }
00229 
00230 
00231 TF2SIMD_FORCE_INLINE int       tf2IsNegative(tf2Scalar x) {
00232     return x < tf2Scalar(0.0) ? 1 : 0;
00233 }
00234 
00235 TF2SIMD_FORCE_INLINE tf2Scalar tf2Radians(tf2Scalar x) { return x * TF2SIMD_RADS_PER_DEG; }
00236 TF2SIMD_FORCE_INLINE tf2Scalar tf2Degrees(tf2Scalar x) { return x * TF2SIMD_DEGS_PER_RAD; }
00237 
00238 #define TF2_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name
00239 
00240 #ifndef tf2Fsel
00241 TF2SIMD_FORCE_INLINE tf2Scalar tf2Fsel(tf2Scalar a, tf2Scalar b, tf2Scalar c)
00242 {
00243         return a >= 0 ? b : c;
00244 }
00245 #endif
00246 #define tf2Fsels(a,b,c) (tf2Scalar)tf2Fsel(a,b,c)
00247 
00248 
00249 TF2SIMD_FORCE_INLINE bool tf2MachineIsLittleEndian()
00250 {
00251    long int i = 1;
00252    const char *p = (const char *) &i;
00253    if (p[0] == 1)  // Lowest address contains the least significant byte
00254            return true;
00255    else
00256            return false;
00257 }
00258 
00259 
00260 
00263 TF2SIMD_FORCE_INLINE unsigned tf2Select(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) 
00264 {
00265     // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero
00266     // Rely on positive value or'ed with its negative having sign bit on
00267     // and zero value or'ed with its negative (which is still zero) having sign bit off 
00268     // Use arithmetic shift right, shifting the sign bit through all 32 bits
00269     unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
00270     unsigned testEqz = ~testNz;
00271     return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); 
00272 }
00273 TF2SIMD_FORCE_INLINE int tf2Select(unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero)
00274 {
00275     unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
00276     unsigned testEqz = ~testNz; 
00277     return static_cast<int>((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz));
00278 }
00279 TF2SIMD_FORCE_INLINE float tf2Select(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero)
00280 {
00281 #ifdef TF2_HAVE_NATIVE_FSEL
00282     return (float)tf2Fsel((tf2Scalar)condition - tf2Scalar(1.0f), valueIfConditionNonZero, valueIfConditionZero);
00283 #else
00284     return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; 
00285 #endif
00286 }
00287 
00288 template<typename T> TF2SIMD_FORCE_INLINE void tf2Swap(T& a, T& b)
00289 {
00290         T tmp = a;
00291         a = b;
00292         b = tmp;
00293 }
00294 
00295 
00296 //PCK: endian swapping functions
00297 TF2SIMD_FORCE_INLINE unsigned tf2SwapEndian(unsigned val)
00298 {
00299         return (((val & 0xff000000) >> 24) | ((val & 0x00ff0000) >> 8) | ((val & 0x0000ff00) << 8)  | ((val & 0x000000ff) << 24));
00300 }
00301 
00302 TF2SIMD_FORCE_INLINE unsigned short tf2SwapEndian(unsigned short val)
00303 {
00304         return static_cast<unsigned short>(((val & 0xff00) >> 8) | ((val & 0x00ff) << 8));
00305 }
00306 
00307 TF2SIMD_FORCE_INLINE unsigned tf2SwapEndian(int val)
00308 {
00309         return tf2SwapEndian((unsigned)val);
00310 }
00311 
00312 TF2SIMD_FORCE_INLINE unsigned short tf2SwapEndian(short val)
00313 {
00314         return tf2SwapEndian((unsigned short) val);
00315 }
00316 
00323 TF2SIMD_FORCE_INLINE unsigned int  tf2SwapEndianFloat(float d)
00324 {
00325     unsigned int a = 0;
00326     unsigned char *dst = (unsigned char *)&a;
00327     unsigned char *src = (unsigned char *)&d;
00328 
00329     dst[0] = src[3];
00330     dst[1] = src[2];
00331     dst[2] = src[1];
00332     dst[3] = src[0];
00333     return a;
00334 }
00335 
00336 // unswap using char pointers
00337 TF2SIMD_FORCE_INLINE float tf2UnswapEndianFloat(unsigned int a) 
00338 {
00339     float d = 0.0f;
00340     unsigned char *src = (unsigned char *)&a;
00341     unsigned char *dst = (unsigned char *)&d;
00342 
00343     dst[0] = src[3];
00344     dst[1] = src[2];
00345     dst[2] = src[1];
00346     dst[3] = src[0];
00347 
00348     return d;
00349 }
00350 
00351 
00352 // swap using char pointers
00353 TF2SIMD_FORCE_INLINE void  tf2SwapEndianDouble(double d, unsigned char* dst)
00354 {
00355     unsigned char *src = (unsigned char *)&d;
00356 
00357     dst[0] = src[7];
00358     dst[1] = src[6];
00359     dst[2] = src[5];
00360     dst[3] = src[4];
00361     dst[4] = src[3];
00362     dst[5] = src[2];
00363     dst[6] = src[1];
00364     dst[7] = src[0];
00365 
00366 }
00367 
00368 // unswap using char pointers
00369 TF2SIMD_FORCE_INLINE double tf2UnswapEndianDouble(const unsigned char *src) 
00370 {
00371     double d = 0.0;
00372     unsigned char *dst = (unsigned char *)&d;
00373 
00374     dst[0] = src[7];
00375     dst[1] = src[6];
00376     dst[2] = src[5];
00377     dst[3] = src[4];
00378     dst[4] = src[3];
00379     dst[5] = src[2];
00380     dst[6] = src[1];
00381     dst[7] = src[0];
00382 
00383         return d;
00384 }
00385 
00386 // returns normalized value in range [-TF2SIMD_PI, TF2SIMD_PI]
00387 TF2SIMD_FORCE_INLINE tf2Scalar tf2NormalizeAngle(tf2Scalar angleInRadians) 
00388 {
00389         angleInRadians = tf2Fmod(angleInRadians, TF2SIMD_2_PI);
00390         if(angleInRadians < -TF2SIMD_PI)
00391         {
00392                 return angleInRadians + TF2SIMD_2_PI;
00393         }
00394         else if(angleInRadians > TF2SIMD_PI)
00395         {
00396                 return angleInRadians - TF2SIMD_2_PI;
00397         }
00398         else
00399         {
00400                 return angleInRadians;
00401         }
00402 }
00403 
00405 struct tf2TypedObject
00406 {
00407         tf2TypedObject(int objectType)
00408                 :m_objectType(objectType)
00409         {
00410         }
00411         int     m_objectType;
00412         inline int getObjectType() const
00413         {
00414                 return m_objectType;
00415         }
00416 };
00417 #endif //TF2SIMD___SCALAR_H


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 20:22:56