btScalar.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 BT_SCALAR_H
00018 #define BT_SCALAR_H
00019 
00020 #ifdef BT_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 <float.h>
00029 
00030 /* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/
00031 #define BT_BULLET_VERSION 279
00032 
00033 inline int      btGetVersion()
00034 {
00035         return BT_BULLET_VERSION;
00036 }
00037 
00038 #if defined(DEBUG) || defined (_DEBUG)
00039 #define BT_DEBUG
00040 #endif
00041 
00042 
00043 #ifdef _WIN32
00044 
00045                 #if defined(__MINGW32__) || defined(__CYGWIN__) || (defined (_MSC_VER) && _MSC_VER < 1300)
00046 
00047                         #define SIMD_FORCE_INLINE inline
00048                         #define ATTRIBUTE_ALIGNED16(a) a
00049                         #define ATTRIBUTE_ALIGNED64(a) a
00050                         #define ATTRIBUTE_ALIGNED128(a) a
00051                 #else
00052                         //#define BT_HAS_ALIGNED_ALLOCATOR
00053                         #pragma warning(disable : 4324) // disable padding warning
00054 //                      #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning.
00055 //                      #pragma warning(disable:4996) //Turn off warnings about deprecated C routines
00056 //                      #pragma warning(disable:4786) // Disable the "debug name too long" warning
00057 
00058                         #define SIMD_FORCE_INLINE __forceinline
00059                         #define ATTRIBUTE_ALIGNED16(a) __declspec(align(16)) a
00060                         #define ATTRIBUTE_ALIGNED64(a) __declspec(align(64)) a
00061                         #define ATTRIBUTE_ALIGNED128(a) __declspec (align(128)) a
00062                 #ifdef _XBOX
00063                         #define BT_USE_VMX128
00064 
00065                         #include <ppcintrinsics.h>
00066                         #define BT_HAVE_NATIVE_FSEL
00067                         #define btFsel(a,b,c) __fsel((a),(b),(c))
00068                 #else
00069 
00070 #if (defined (_WIN32) && (_MSC_VER) && _MSC_VER >= 1400) && (!defined (BT_USE_DOUBLE_PRECISION))
00071                         #define BT_USE_SSE
00072                         #include <emmintrin.h>
00073 #endif
00074 
00075                 #endif//_XBOX
00076 
00077                 #endif //__MINGW32__
00078 
00079                 #include <assert.h>
00080 #ifdef BT_DEBUG
00081                 #define btAssert assert
00082 #else
00083                 #define btAssert(x)
00084 #endif
00085                 //btFullAssert is optional, slows down a lot
00086                 #define btFullAssert(x)
00087 
00088                 #define btLikely(_c)  _c
00089                 #define btUnlikely(_c) _c
00090 
00091 #else
00092         
00093 #if defined     (__CELLOS_LV2__)
00094                 #define SIMD_FORCE_INLINE inline __attribute__((always_inline))
00095                 #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16)))
00096                 #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64)))
00097                 #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128)))
00098                 #ifndef assert
00099                 #include <assert.h>
00100                 #endif
00101 #ifdef BT_DEBUG
00102 #ifdef __SPU__
00103 #include <spu_printf.h>
00104 #define printf spu_printf
00105         #define btAssert(x) {if(!(x)){printf("Assert "__FILE__ ":%u ("#x")\n", __LINE__);spu_hcmpeq(0,0);}}
00106 #else
00107         #define btAssert assert
00108 #endif
00109         
00110 #else
00111                 #define btAssert(x)
00112 #endif
00113                 //btFullAssert is optional, slows down a lot
00114                 #define btFullAssert(x)
00115 
00116                 #define btLikely(_c)  _c
00117                 #define btUnlikely(_c) _c
00118 
00119 #else
00120 
00121 #ifdef USE_LIBSPE2
00122 
00123                 #define SIMD_FORCE_INLINE __inline
00124                 #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16)))
00125                 #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64)))
00126                 #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128)))
00127                 #ifndef assert
00128                 #include <assert.h>
00129                 #endif
00130 #ifdef BT_DEBUG
00131                 #define btAssert assert
00132 #else
00133                 #define btAssert(x)
00134 #endif
00135                 //btFullAssert is optional, slows down a lot
00136                 #define btFullAssert(x)
00137 
00138 
00139                 #define btLikely(_c)   __builtin_expect((_c), 1)
00140                 #define btUnlikely(_c) __builtin_expect((_c), 0)
00141                 
00142 
00143 #else
00144         //non-windows systems
00145 
00146 #if (defined (__APPLE__) && defined (__i386__) && (!defined (BT_USE_DOUBLE_PRECISION)))
00147         #define BT_USE_SSE
00148         #include <emmintrin.h>
00149 
00150         #define SIMD_FORCE_INLINE inline
00151 
00152         #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16)))
00153         #define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64)))
00154         #define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128)))
00155         #ifndef assert
00156         #include <assert.h>
00157         #endif
00158 
00159         #if defined(DEBUG) || defined (_DEBUG)
00160                 #define btAssert assert
00161         #else
00162                 #define btAssert(x)
00163         #endif
00164 
00165         //btFullAssert is optional, slows down a lot
00166         #define btFullAssert(x)
00167         #define btLikely(_c)  _c
00168         #define btUnlikely(_c) _c
00169 
00170 #else
00171 
00172                 #define SIMD_FORCE_INLINE inline
00173 
00174 
00175 
00176 
00177                 #define ATTRIBUTE_ALIGNED16(a) a
00178                 #define ATTRIBUTE_ALIGNED64(a) a
00179                 #define ATTRIBUTE_ALIGNED128(a) a
00180                 #ifndef assert
00181                 #include <assert.h>
00182                 #endif
00183 
00184 #if defined(DEBUG) || defined (_DEBUG)
00185                 #define btAssert assert
00186 #else
00187                 #define btAssert(x)
00188 #endif
00189 
00190                 //btFullAssert is optional, slows down a lot
00191                 #define btFullAssert(x)
00192                 #define btLikely(_c)  _c
00193                 #define btUnlikely(_c) _c
00194 #endif //__APPLE__ 
00195 
00196 #endif // LIBSPE2
00197 
00198 #endif  //__CELLOS_LV2__
00199 #endif
00200 
00201 
00203 #if defined(BT_USE_DOUBLE_PRECISION)
00204 typedef double btScalar;
00205 //this number could be bigger in double precision
00206 #define BT_LARGE_FLOAT 1e30
00207 #else
00208 typedef float btScalar;
00209 //keep BT_LARGE_FLOAT*BT_LARGE_FLOAT < FLT_MAX
00210 #define BT_LARGE_FLOAT 1e18f
00211 #endif
00212 
00213 
00214 
00215 #define BT_DECLARE_ALIGNED_ALLOCATOR() \
00216    SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes)   { return btAlignedAlloc(sizeInBytes,16); }   \
00217    SIMD_FORCE_INLINE void  operator delete(void* ptr)         { btAlignedFree(ptr); }   \
00218    SIMD_FORCE_INLINE void* operator new(size_t, void* ptr)   { return ptr; }   \
00219    SIMD_FORCE_INLINE void  operator delete(void*, void*)      { }   \
00220    SIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes)   { return btAlignedAlloc(sizeInBytes,16); }   \
00221    SIMD_FORCE_INLINE void  operator delete[](void* ptr)         { btAlignedFree(ptr); }   \
00222    SIMD_FORCE_INLINE void* operator new[](size_t, void* ptr)   { return ptr; }   \
00223    SIMD_FORCE_INLINE void  operator delete[](void*, void*)      { }   \
00224 
00225 
00226 
00227 #if defined(BT_USE_DOUBLE_PRECISION) || defined(BT_FORCE_DOUBLE_FUNCTIONS)
00228                 
00229 SIMD_FORCE_INLINE btScalar btSqrt(btScalar x) { return sqrt(x); }
00230 SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabs(x); }
00231 SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cos(x); }
00232 SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sin(x); }
00233 SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tan(x); }
00234 SIMD_FORCE_INLINE btScalar btAcos(btScalar x) { if (x<btScalar(-1))     x=btScalar(-1); if (x>btScalar(1))      x=btScalar(1); return acos(x); }
00235 SIMD_FORCE_INLINE btScalar btAsin(btScalar x) { if (x<btScalar(-1))     x=btScalar(-1); if (x>btScalar(1))      x=btScalar(1); return asin(x); }
00236 SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atan(x); }
00237 SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2(x, y); }
00238 SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return exp(x); }
00239 SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return log(x); }
00240 SIMD_FORCE_INLINE btScalar btPow(btScalar x,btScalar y) { return pow(x,y); }
00241 SIMD_FORCE_INLINE btScalar btFmod(btScalar x,btScalar y) { return fmod(x,y); }
00242 
00243 #else
00244                 
00245 SIMD_FORCE_INLINE btScalar btSqrt(btScalar y) 
00246 { 
00247 #ifdef USE_APPROXIMATION
00248     double x, z, tempf;
00249     unsigned long *tfptr = ((unsigned long *)&tempf) + 1;
00250 
00251         tempf = y;
00252         *tfptr = (0xbfcdd90a - *tfptr)>>1; /* estimate of 1/sqrt(y) */
00253         x =  tempf;
00254         z =  y*btScalar(0.5);
00255         x = (btScalar(1.5)*x)-(x*x)*(x*z);         /* iteration formula     */
00256         x = (btScalar(1.5)*x)-(x*x)*(x*z);
00257         x = (btScalar(1.5)*x)-(x*x)*(x*z);
00258         x = (btScalar(1.5)*x)-(x*x)*(x*z);
00259         x = (btScalar(1.5)*x)-(x*x)*(x*z);
00260         return x*y;
00261 #else
00262         return sqrtf(y); 
00263 #endif
00264 }
00265 SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabsf(x); }
00266 SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cosf(x); }
00267 SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sinf(x); }
00268 SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tanf(x); }
00269 SIMD_FORCE_INLINE btScalar btAcos(btScalar x) { 
00270         if (x<btScalar(-1))     
00271                 x=btScalar(-1); 
00272         if (x>btScalar(1))      
00273                 x=btScalar(1);
00274         return acosf(x); 
00275 }
00276 SIMD_FORCE_INLINE btScalar btAsin(btScalar x) { 
00277         if (x<btScalar(-1))     
00278                 x=btScalar(-1); 
00279         if (x>btScalar(1))      
00280                 x=btScalar(1);
00281         return asinf(x); 
00282 }
00283 SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atanf(x); }
00284 SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2f(x, y); }
00285 SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return expf(x); }
00286 SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return logf(x); }
00287 SIMD_FORCE_INLINE btScalar btPow(btScalar x,btScalar y) { return powf(x,y); }
00288 SIMD_FORCE_INLINE btScalar btFmod(btScalar x,btScalar y) { return fmodf(x,y); }
00289         
00290 #endif
00291 
00292 #define SIMD_2_PI         btScalar(6.283185307179586232)
00293 #define SIMD_PI           (SIMD_2_PI * btScalar(0.5))
00294 #define SIMD_HALF_PI      (SIMD_2_PI * btScalar(0.25))
00295 #define SIMD_RADS_PER_DEG (SIMD_2_PI / btScalar(360.0))
00296 #define SIMD_DEGS_PER_RAD  (btScalar(360.0) / SIMD_2_PI)
00297 #define SIMDSQRT12 btScalar(0.7071067811865475244008443621048490)
00298 
00299 #define btRecipSqrt(x) ((btScalar)(btScalar(1.0)/btSqrt(btScalar(x))))          /* reciprocal square root */
00300 
00301 
00302 #ifdef BT_USE_DOUBLE_PRECISION
00303 #define SIMD_EPSILON      DBL_EPSILON
00304 #define SIMD_INFINITY     DBL_MAX
00305 #else
00306 #define SIMD_EPSILON      FLT_EPSILON
00307 #define SIMD_INFINITY     FLT_MAX
00308 #endif
00309 
00310 SIMD_FORCE_INLINE btScalar btAtan2Fast(btScalar y, btScalar x) 
00311 {
00312         btScalar coeff_1 = SIMD_PI / 4.0f;
00313         btScalar coeff_2 = 3.0f * coeff_1;
00314         btScalar abs_y = btFabs(y);
00315         btScalar angle;
00316         if (x >= 0.0f) {
00317                 btScalar r = (x - abs_y) / (x + abs_y);
00318                 angle = coeff_1 - coeff_1 * r;
00319         } else {
00320                 btScalar r = (x + abs_y) / (abs_y - x);
00321                 angle = coeff_2 - coeff_1 * r;
00322         }
00323         return (y < 0.0f) ? -angle : angle;
00324 }
00325 
00326 SIMD_FORCE_INLINE bool      btFuzzyZero(btScalar x) { return btFabs(x) < SIMD_EPSILON; }
00327 
00328 SIMD_FORCE_INLINE bool  btEqual(btScalar a, btScalar eps) {
00329         return (((a) <= eps) && !((a) < -eps));
00330 }
00331 SIMD_FORCE_INLINE bool  btGreaterEqual (btScalar a, btScalar eps) {
00332         return (!((a) <= eps));
00333 }
00334 
00335 
00336 SIMD_FORCE_INLINE int       btIsNegative(btScalar x) {
00337     return x < btScalar(0.0) ? 1 : 0;
00338 }
00339 
00340 SIMD_FORCE_INLINE btScalar btRadians(btScalar x) { return x * SIMD_RADS_PER_DEG; }
00341 SIMD_FORCE_INLINE btScalar btDegrees(btScalar x) { return x * SIMD_DEGS_PER_RAD; }
00342 
00343 #define BT_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name
00344 
00345 #ifndef btFsel
00346 SIMD_FORCE_INLINE btScalar btFsel(btScalar a, btScalar b, btScalar c)
00347 {
00348         return a >= 0 ? b : c;
00349 }
00350 #endif
00351 #define btFsels(a,b,c) (btScalar)btFsel(a,b,c)
00352 
00353 
00354 SIMD_FORCE_INLINE bool btMachineIsLittleEndian()
00355 {
00356    long int i = 1;
00357    const char *p = (const char *) &i;
00358    if (p[0] == 1)  // Lowest address contains the least significant byte
00359            return true;
00360    else
00361            return false;
00362 }
00363 
00364 
00365 
00368 SIMD_FORCE_INLINE unsigned btSelect(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) 
00369 {
00370     // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero
00371     // Rely on positive value or'ed with its negative having sign bit on
00372     // and zero value or'ed with its negative (which is still zero) having sign bit off 
00373     // Use arithmetic shift right, shifting the sign bit through all 32 bits
00374     unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
00375     unsigned testEqz = ~testNz;
00376     return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); 
00377 }
00378 SIMD_FORCE_INLINE int btSelect(unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero)
00379 {
00380     unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
00381     unsigned testEqz = ~testNz; 
00382     return static_cast<int>((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz));
00383 }
00384 SIMD_FORCE_INLINE float btSelect(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero)
00385 {
00386 #ifdef BT_HAVE_NATIVE_FSEL
00387     return (float)btFsel((btScalar)condition - btScalar(1.0f), valueIfConditionNonZero, valueIfConditionZero);
00388 #else
00389     return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; 
00390 #endif
00391 }
00392 
00393 template<typename T> SIMD_FORCE_INLINE void btSwap(T& a, T& b)
00394 {
00395         T tmp = a;
00396         a = b;
00397         b = tmp;
00398 }
00399 
00400 
00401 //PCK: endian swapping functions
00402 SIMD_FORCE_INLINE unsigned btSwapEndian(unsigned val)
00403 {
00404         return (((val & 0xff000000) >> 24) | ((val & 0x00ff0000) >> 8) | ((val & 0x0000ff00) << 8)  | ((val & 0x000000ff) << 24));
00405 }
00406 
00407 SIMD_FORCE_INLINE unsigned short btSwapEndian(unsigned short val)
00408 {
00409         return static_cast<unsigned short>(((val & 0xff00) >> 8) | ((val & 0x00ff) << 8));
00410 }
00411 
00412 SIMD_FORCE_INLINE unsigned btSwapEndian(int val)
00413 {
00414         return btSwapEndian((unsigned)val);
00415 }
00416 
00417 SIMD_FORCE_INLINE unsigned short btSwapEndian(short val)
00418 {
00419         return btSwapEndian((unsigned short) val);
00420 }
00421 
00428 SIMD_FORCE_INLINE unsigned int  btSwapEndianFloat(float d)
00429 {
00430     unsigned int a = 0;
00431     unsigned char *dst = (unsigned char *)&a;
00432     unsigned char *src = (unsigned char *)&d;
00433 
00434     dst[0] = src[3];
00435     dst[1] = src[2];
00436     dst[2] = src[1];
00437     dst[3] = src[0];
00438     return a;
00439 }
00440 
00441 // unswap using char pointers
00442 SIMD_FORCE_INLINE float btUnswapEndianFloat(unsigned int a) 
00443 {
00444     float d = 0.0f;
00445     unsigned char *src = (unsigned char *)&a;
00446     unsigned char *dst = (unsigned char *)&d;
00447 
00448     dst[0] = src[3];
00449     dst[1] = src[2];
00450     dst[2] = src[1];
00451     dst[3] = src[0];
00452 
00453     return d;
00454 }
00455 
00456 
00457 // swap using char pointers
00458 SIMD_FORCE_INLINE void  btSwapEndianDouble(double d, unsigned char* dst)
00459 {
00460     unsigned char *src = (unsigned char *)&d;
00461 
00462     dst[0] = src[7];
00463     dst[1] = src[6];
00464     dst[2] = src[5];
00465     dst[3] = src[4];
00466     dst[4] = src[3];
00467     dst[5] = src[2];
00468     dst[6] = src[1];
00469     dst[7] = src[0];
00470 
00471 }
00472 
00473 // unswap using char pointers
00474 SIMD_FORCE_INLINE double btUnswapEndianDouble(const unsigned char *src) 
00475 {
00476     double d = 0.0;
00477     unsigned char *dst = (unsigned char *)&d;
00478 
00479     dst[0] = src[7];
00480     dst[1] = src[6];
00481     dst[2] = src[5];
00482     dst[3] = src[4];
00483     dst[4] = src[3];
00484     dst[5] = src[2];
00485     dst[6] = src[1];
00486     dst[7] = src[0];
00487 
00488         return d;
00489 }
00490 
00491 // returns normalized value in range [-SIMD_PI, SIMD_PI]
00492 SIMD_FORCE_INLINE btScalar btNormalizeAngle(btScalar angleInRadians) 
00493 {
00494         angleInRadians = btFmod(angleInRadians, SIMD_2_PI);
00495         if(angleInRadians < -SIMD_PI)
00496         {
00497                 return angleInRadians + SIMD_2_PI;
00498         }
00499         else if(angleInRadians > SIMD_PI)
00500         {
00501                 return angleInRadians - SIMD_2_PI;
00502         }
00503         else
00504         {
00505                 return angleInRadians;
00506         }
00507 }
00508 
00510 struct btTypedObject
00511 {
00512         btTypedObject(int objectType)
00513                 :m_objectType(objectType)
00514         {
00515         }
00516         int     m_objectType;
00517         inline int getObjectType() const
00518         {
00519                 return m_objectType;
00520         }
00521 };
00522 #endif //BT_SCALAR_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31