tf2 rolling
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Loading...
Searching...
No Matches
Classes | Macros | Typedefs | Functions
Scalar.hpp File Reference
#include <math.h>
#include <stdlib.h>
#include <cstdlib>
#include <cfloat>
#include <float.h>
#include <assert.h>
Include dependency graph for Scalar.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  tf2TypedObject
 rudimentary class to provide type info More...
 

Macros

#define TF2SIMD_FORCE_INLINE   inline
 
#define ATTRIBUTE_ALIGNED16(a)   a
 
#define ATTRIBUTE_ALIGNED64(a)   a
 
#define ATTRIBUTE_ALIGNED128(a)   a
 
#define tf2Assert(x)
 
#define tf2FullAssert(x)
 
#define tf2Likely(_c)   _c
 
#define tf2Unlikely(_c)   _c
 
#define TF2_LARGE_FLOAT   1e30
 
#define TF2_DECLARE_ALIGNED_ALLOCATOR()
 
#define TF2SIMD_2_PI   tf2Scalar(6.283185307179586232)
 
#define TF2SIMD_PI   (TF2SIMD_2_PI * tf2Scalar(0.5))
 
#define TF2SIMD_HALF_PI   (TF2SIMD_2_PI * tf2Scalar(0.25))
 
#define TF2SIMD_RADS_PER_DEG   (TF2SIMD_2_PI / tf2Scalar(360.0))
 
#define TF2SIMD_DEGS_PER_RAD   (tf2Scalar(360.0) / TF2SIMD_2_PI)
 
#define TF2SIMDSQRT12   tf2Scalar(0.7071067811865475244008443621048490)
 
#define tf2RecipSqrt(x)   ((tf2Scalar)(tf2Scalar(1.0)/tf2Sqrt(tf2Scalar(x)))) /* reciprocal square root */
 
#define TF2SIMD_EPSILON   DBL_EPSILON
 
#define TF2SIMD_INFINITY   DBL_MAX
 
#define TF2_DECLARE_HANDLE(name)   typedef struct name##__ { int unused; } *name
 
#define tf2Fsels(a, b, c)   (tf2Scalar)tf2Fsel(a,b,c)
 

Typedefs

typedef double tf2Scalar
 The tf2Scalar type abstracts floating point numbers, to easily switch between double and single floating point precision.
 

Functions

tf2Scalar tf2Sqrt (tf2Scalar x)
 
tf2Scalar tf2Fabs (tf2Scalar x)
 
tf2Scalar tf2Cos (tf2Scalar x)
 
tf2Scalar tf2Sin (tf2Scalar x)
 
tf2Scalar tf2Tan (tf2Scalar x)
 
tf2Scalar tf2Acos (tf2Scalar x)
 
tf2Scalar tf2Asin (tf2Scalar x)
 
tf2Scalar tf2Atan (tf2Scalar x)
 
tf2Scalar tf2Atan2 (tf2Scalar x, tf2Scalar y)
 
tf2Scalar tf2Exp (tf2Scalar x)
 
tf2Scalar tf2Log (tf2Scalar x)
 
tf2Scalar tf2Pow (tf2Scalar x, tf2Scalar y)
 
tf2Scalar tf2Fmod (tf2Scalar x, tf2Scalar y)
 
tf2Scalar tf2Atan2Fast (tf2Scalar y, tf2Scalar x)
 
bool tf2FuzzyZero (tf2Scalar x)
 
bool tf2Equal (tf2Scalar a, tf2Scalar eps)
 
bool tf2GreaterEqual (tf2Scalar a, tf2Scalar eps)
 
int tf2IsNegative (tf2Scalar x)
 
tf2Scalar tf2Radians (tf2Scalar x)
 
tf2Scalar tf2Degrees (tf2Scalar x)
 
tf2Scalar tf2Fsel (tf2Scalar a, tf2Scalar b, tf2Scalar c)
 
bool tf2MachineIsLittleEndian ()
 
unsigned tf2Select (unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero)
 
int tf2Select (unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero)
 
float tf2Select (unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero)
 
template<typename T >
void tf2Swap (T &a, T &b)
 
unsigned tf2SwapEndian (unsigned val)
 
unsigned short tf2SwapEndian (unsigned short val)
 
unsigned tf2SwapEndian (int val)
 
unsigned short tf2SwapEndian (short val)
 
unsigned int tf2SwapEndianFloat (float d)
 tf2SwapFloat uses using char pointers to swap the endianness
 
float tf2UnswapEndianFloat (unsigned int a)
 
void tf2SwapEndianDouble (double d, unsigned char *dst)
 
double tf2UnswapEndianDouble (const unsigned char *src)
 
tf2Scalar tf2NormalizeAngle (tf2Scalar angleInRadians)
 

Macro Definition Documentation

◆ TF2SIMD_FORCE_INLINE

#define TF2SIMD_FORCE_INLINE   inline

◆ ATTRIBUTE_ALIGNED16

#define ATTRIBUTE_ALIGNED16 (   a)    a
Todo:
: check out alignment methods for other platforms/compilers define ATTRIBUTE_ALIGNED16(a) a attribute ((aligned (16))) define ATTRIBUTE_ALIGNED64(a) a attribute ((aligned (64))) define ATTRIBUTE_ALIGNED128(a) a attribute ((aligned (128)))

◆ ATTRIBUTE_ALIGNED64

#define ATTRIBUTE_ALIGNED64 (   a)    a

◆ ATTRIBUTE_ALIGNED128

#define ATTRIBUTE_ALIGNED128 (   a)    a

◆ tf2Assert

#define tf2Assert (   x)

◆ tf2FullAssert

#define tf2FullAssert (   x)

◆ tf2Likely

#define tf2Likely (   _c)    _c

◆ tf2Unlikely

#define tf2Unlikely (   _c)    _c

◆ TF2_LARGE_FLOAT

#define TF2_LARGE_FLOAT   1e30

◆ TF2_DECLARE_ALIGNED_ALLOCATOR

#define TF2_DECLARE_ALIGNED_ALLOCATOR ( )
Value:
TF2SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes) { return tf2AlignedAlloc(sizeInBytes,16); } \
TF2SIMD_FORCE_INLINE void operator delete(void* ptr) { tf2AlignedFree(ptr); } \
TF2SIMD_FORCE_INLINE void* operator new(size_t, void* ptr) { return ptr; } \
TF2SIMD_FORCE_INLINE void operator delete(void*, void*) { } \
TF2SIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes) { return tf2AlignedAlloc(sizeInBytes,16); } \
TF2SIMD_FORCE_INLINE void operator delete[](void* ptr) { tf2AlignedFree(ptr); } \
TF2SIMD_FORCE_INLINE void* operator new[](size_t, void* ptr) { return ptr; } \
TF2SIMD_FORCE_INLINE void operator delete[](void*, void*) { } \
#define TF2SIMD_FORCE_INLINE
Definition Scalar.hpp:129

◆ TF2SIMD_2_PI

#define TF2SIMD_2_PI   tf2Scalar(6.283185307179586232)

◆ TF2SIMD_PI

#define TF2SIMD_PI   (TF2SIMD_2_PI * tf2Scalar(0.5))

◆ TF2SIMD_HALF_PI

#define TF2SIMD_HALF_PI   (TF2SIMD_2_PI * tf2Scalar(0.25))

◆ TF2SIMD_RADS_PER_DEG

#define TF2SIMD_RADS_PER_DEG   (TF2SIMD_2_PI / tf2Scalar(360.0))

◆ TF2SIMD_DEGS_PER_RAD

#define TF2SIMD_DEGS_PER_RAD   (tf2Scalar(360.0) / TF2SIMD_2_PI)

◆ TF2SIMDSQRT12

#define TF2SIMDSQRT12   tf2Scalar(0.7071067811865475244008443621048490)

◆ tf2RecipSqrt

#define tf2RecipSqrt (   x)    ((tf2Scalar)(tf2Scalar(1.0)/tf2Sqrt(tf2Scalar(x)))) /* reciprocal square root */

◆ TF2SIMD_EPSILON

#define TF2SIMD_EPSILON   DBL_EPSILON

◆ TF2SIMD_INFINITY

#define TF2SIMD_INFINITY   DBL_MAX

◆ TF2_DECLARE_HANDLE

#define TF2_DECLARE_HANDLE (   name)    typedef struct name##__ { int unused; } *name

◆ tf2Fsels

#define tf2Fsels (   a,
  b,
 
)    (tf2Scalar)tf2Fsel(a,b,c)

Typedef Documentation

◆ tf2Scalar

typedef double tf2Scalar

The tf2Scalar type abstracts floating point numbers, to easily switch between double and single floating point precision.

Function Documentation

◆ tf2Sqrt()

tf2Scalar tf2Sqrt ( tf2Scalar  x)

◆ tf2Fabs()

tf2Scalar tf2Fabs ( tf2Scalar  x)

◆ tf2Cos()

tf2Scalar tf2Cos ( tf2Scalar  x)

◆ tf2Sin()

tf2Scalar tf2Sin ( tf2Scalar  x)

◆ tf2Tan()

tf2Scalar tf2Tan ( tf2Scalar  x)

◆ tf2Acos()

tf2Scalar tf2Acos ( tf2Scalar  x)

◆ tf2Asin()

tf2Scalar tf2Asin ( tf2Scalar  x)

◆ tf2Atan()

tf2Scalar tf2Atan ( tf2Scalar  x)

◆ tf2Atan2()

tf2Scalar tf2Atan2 ( tf2Scalar  x,
tf2Scalar  y 
)

◆ tf2Exp()

tf2Scalar tf2Exp ( tf2Scalar  x)

◆ tf2Log()

tf2Scalar tf2Log ( tf2Scalar  x)

◆ tf2Pow()

tf2Scalar tf2Pow ( tf2Scalar  x,
tf2Scalar  y 
)

◆ tf2Fmod()

tf2Scalar tf2Fmod ( tf2Scalar  x,
tf2Scalar  y 
)

◆ tf2Atan2Fast()

tf2Scalar tf2Atan2Fast ( tf2Scalar  y,
tf2Scalar  x 
)

◆ tf2FuzzyZero()

bool tf2FuzzyZero ( tf2Scalar  x)

◆ tf2Equal()

bool tf2Equal ( tf2Scalar  a,
tf2Scalar  eps 
)

◆ tf2GreaterEqual()

bool tf2GreaterEqual ( tf2Scalar  a,
tf2Scalar  eps 
)

◆ tf2IsNegative()

int tf2IsNegative ( tf2Scalar  x)

◆ tf2Radians()

tf2Scalar tf2Radians ( tf2Scalar  x)

◆ tf2Degrees()

tf2Scalar tf2Degrees ( tf2Scalar  x)

◆ tf2Fsel()

tf2Scalar tf2Fsel ( tf2Scalar  a,
tf2Scalar  b,
tf2Scalar  c 
)

◆ tf2MachineIsLittleEndian()

bool tf2MachineIsLittleEndian ( )

◆ tf2Select() [1/3]

unsigned tf2Select ( unsigned  condition,
unsigned  valueIfConditionNonZero,
unsigned  valueIfConditionZero 
)

tf2Select avoids branches, which makes performance much better for consoles like Playstation 3 and XBox 360 Thanks Phil Knight. See also http://www.cellperformance.com/articles/2006/04/more_techniques_for_eliminatin_1.html

◆ tf2Select() [2/3]

int tf2Select ( unsigned  condition,
int  valueIfConditionNonZero,
int  valueIfConditionZero 
)

◆ tf2Select() [3/3]

float tf2Select ( unsigned  condition,
float  valueIfConditionNonZero,
float  valueIfConditionZero 
)

◆ tf2Swap()

template<typename T >
void tf2Swap ( T &  a,
T &  b 
)

◆ tf2SwapEndian() [1/4]

unsigned tf2SwapEndian ( unsigned  val)

◆ tf2SwapEndian() [2/4]

unsigned short tf2SwapEndian ( unsigned short  val)

◆ tf2SwapEndian() [3/4]

unsigned tf2SwapEndian ( int  val)

◆ tf2SwapEndian() [4/4]

unsigned short tf2SwapEndian ( short  val)

◆ tf2SwapEndianFloat()

unsigned int tf2SwapEndianFloat ( float  d)

tf2SwapFloat uses using char pointers to swap the endianness

tf2SwapFloat/tf2SwapDouble will NOT return a float, because the machine might 'correct' invalid floating point values Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. so instead of returning a float/double, we return integer/long long integer

◆ tf2UnswapEndianFloat()

float tf2UnswapEndianFloat ( unsigned int  a)

◆ tf2SwapEndianDouble()

void tf2SwapEndianDouble ( double  d,
unsigned char *  dst 
)

◆ tf2UnswapEndianDouble()

double tf2UnswapEndianDouble ( const unsigned char *  src)

◆ tf2NormalizeAngle()

tf2Scalar tf2NormalizeAngle ( tf2Scalar  angleInRadians)