Defines basic math and gemoetric primitives. dReal is defined in ODE. Any functions not in here like conversions between quaterions and matrices are most likely defined in ODE.
|
template<class T > |
T * | _cross3 (T *pfout, const T *pf1, const T *pf2) |
|
template<class T > |
T | _dot2 (const T *pf1, const T *pf2) |
|
template<class T > |
T | _dot3 (const T *pf1, const T *pf2) |
|
template<class T > |
T | _dot4 (const T *pf1, const T *pf2) |
|
template<class T > |
T * | _inv3 (const T *pf, T *pfres, T *pfdet, int stride) |
|
template<class T > |
T * | _inv4 (const T *pf, T *pfres) |
|
template<class T > |
T | _lengthsqr2 (const T *pf) |
|
template<class T > |
T | _lengthsqr3 (const T *pf) |
|
template<class T > |
T | _lengthsqr4 (const T *pf) |
|
template<class T > |
T * | _mult3_s3 (T *pfres, const T *pf1, const T *pf2) |
| mult3 with a 3x3 matrix whose row stride is 12 bytes More...
|
|
template<class T > |
T * | _mult3_s4 (T *pfres, const T *pf1, const T *pf2) |
| mult3 with a 3x3 matrix whose row stride is 16 bytes More...
|
|
template<class T > |
T * | _mult4 (T *pfres, const T *p1, const T *p2) |
|
template<class T > |
T * | _multtrans3 (T *pfres, const T *pf1, const T *pf2) |
|
template<class T > |
T * | _multtrans4 (T *pfres, const T *pf1, const T *pf2) |
|
template<class T > |
T * | _normalize2 (T *pfout, const T *pf) |
|
template<class T > |
T * | _normalize3 (T *pfout, const T *pf) |
|
template<class T > |
T * | _normalize4 (T *pfout, const T *pf) |
|
template<class T > |
T * | _transnorm3 (T *pfout, const T *pfmat, const T *pf) |
|
template<class T > |
T * | _transpose3 (const T *pf, T *pfres) |
|
template<class T > |
T * | _transpose4 (const T *pf, T *pfres) |
|
template<class T > |
void | add (T *pf1, T *pf2, int r) |
|
template<class T > |
RaveVector< T > | AxisAngle2Quat (const RaveVector< T > &rotaxis, T angle) |
|
float * | cross3 (float *pfout, const float *pf1, const float *pf2) |
|
double * | cross3 (double *pfout, const double *pf1, const double *pf2) |
|
int | CubicRoots (double c0, double c1, double c2, double *r0, double *r1, double *r2) |
|
dReal | DistVertexOBBSq (const Vector &v, const OBB &o) |
|
template<class T > |
T | dot (T *pf1, T *pf2, int length) |
|
float | dot2 (const float *pf1, const float *pf2) |
|
double | dot2 (const double *pf1, const double *pf2) |
|
float | dot3 (const float *pf1, const float *pf2) |
|
double | dot3 (const double *pf1, const double *pf2) |
|
float | dot4 (const float *pf1, const float *pf2) |
|
double | dot4 (const double *pf1, const double *pf2) |
|
void | dQfromR (dQuaternion q, const dMatrix3 R) |
|
void | dQMultiply0 (dQuaternion qa, const dQuaternion qb, const dQuaternion qc) |
|
template<class T > |
RaveVector< T > | dQSlerp (const RaveVector< T > &qa, const RaveVector< T > &qb, T t) |
|
void | dRfromQ (dMatrix3 R, const dQuaternion q) |
|
bool | eig2 (const dReal *pfmat, dReal *peigs, dReal &fv1x, dReal &fv1y, dReal &fv2x, dReal &fv2y) |
|
void | EigenSymmetric3 (dReal *fCovariance, dReal *eval, dReal *fAxes) |
|
void | GetCovarBasisVectors (dReal fCovariance[3][3], Vector *vRight, Vector *vUp, Vector *vDir) |
|
Vector | GetRandomQuat (void) |
|
int | insideQuadrilateral (const Vector *p0, const Vector *p1, const Vector *p2, const Vector *p3) |
|
int | insideTriangle (const Vector *p0, const Vector *p1, const Vector *p2) |
|
template<class T > |
bool | inv2 (T *pf, T *pfres) |
|
float * | inv3 (const float *pf, float *pfres, float *pfdet, int stride) |
|
double * | inv3 (const double *pf, double *pfres, double *pfdet, int stride) |
|
float * | inv4 (const float *pf, float *pfres) |
|
double * | inv4 (const double *pf, double *pfres) |
|
template<class T > |
T | lengthsqr (const T *pf1, const T *pf2, int length) |
|
float | lengthsqr2 (const float *pf) |
|
double | lengthsqr2 (const double *pf) |
|
float | lengthsqr3 (const float *pf) |
|
double | lengthsqr3 (const double *pf) |
|
float | lengthsqr4 (const float *pf) |
|
double | lengthsqr4 (const double *pf) |
|
template<class T > |
T | matrixdet3 (const T *pf, int stride) |
| calculates the determinant of a 3x3 matrix whose row stride stride elements More...
|
|
template<class T > |
int | Max (T *pts, int stride, int numPts) |
|
template<class T > |
int | Min (T *pts, int stride, int numPts) |
|
template<class T > |
void | mult (T *pf, T fa, int r) |
|
template<class T , class R , class S > |
S * | mult (T *pf1, R *pf2, int r1, int c1, int c2, S *pfres, bool badd=false) |
|
float * | mult3_s3 (float *pfres, const float *pf1, const float *pf2) |
|
double * | mult3_s3 (double *pfres, const double *pf1, const double *pf2) |
|
float * | mult3_s4 (float *pfres, const float *pf1, const float *pf2) |
|
double * | mult3_s4 (double *pfres, const double *pf1, const double *pf2) |
|
float * | mult4 (float *pfres, const float *pf1, const float *pf2) |
|
double * | mult4 (double *pfres, const double *pf1, const double *pf2) |
|
template<class T > |
T * | multto1 (T *pf1, T *pf2, int r1, int c1, T *pftemp=NULL) |
|
template<class T , class S > |
T * | multto2 (T *pf1, S *pf2, int r2, int c2, S *pftemp=NULL) |
|
template<class T , class R , class S > |
S * | multtrans (T *pf1, R *pf2, int r1, int c1, int c2, S *pfres, bool badd=false) |
|
float * | multtrans3 (float *pfres, const float *pf1, const float *pf2) |
|
double * | multtrans3 (double *pfres, const double *pf1, const double *pf2) |
|
float * | multtrans4 (float *pfres, const float *pf1, const float *pf2) |
|
double * | multtrans4 (double *pfres, const double *pf1, const double *pf2) |
|
template<class T , class R , class S > |
S * | multtrans_to2 (T *pf1, R *pf2, int r1, int c1, int r2, S *pfres, bool badd=false) |
|
float * | normalize2 (float *pfout, const float *pf) |
|
double * | normalize2 (double *pfout, const double *pf) |
|
float * | normalize3 (float *pfout, const float *pf) |
|
double * | normalize3 (double *pfout, const double *pf) |
|
float * | normalize4 (float *pfout, const float *pf) |
|
double * | normalize4 (double *pfout, const double *pf) |
|
template<class T > |
T | normsqr (const T *pf1, int r) |
|
template<class T > |
RaveVector< T > | operator* (float f, const RaveVector< T > &left) |
|
template<class T > |
RaveVector< T > | operator* (double f, const RaveVector< T > &left) |
|
template<class T , class U > |
std::basic_ostream< T > & | operator<< (std::basic_ostream< T > &O, const RaveVector< U > &v) |
|
template<class T , class U > |
std::basic_ostream< T > & | operator<< (std::basic_ostream< T > &O, const RaveTransform< U > &v) |
|
template<class T , class U > |
std::basic_ostream< T > & | operator<< (std::basic_ostream< T > &O, const RaveTransformMatrix< U > &v) |
|
template<class T , class U > |
std::basic_istream< T > & | operator>> (std::basic_istream< T > &I, RaveVector< U > &v) |
|
template<class T , class U > |
std::basic_istream< T > & | operator>> (std::basic_istream< T > &I, RaveTransform< U > &v) |
|
template<class T , class U > |
std::basic_istream< T > & | operator>> (std::basic_istream< T > &I, RaveTransformMatrix< U > &v) |
|
bool | QLAlgorithm3 (float *m_aafEntry, float *afDiag, float *afSubDiag) |
|
bool | QLAlgorithm3 (double *m_aafEntry, double *afDiag, double *afSubDiag) |
|
void | QuadraticSolver (dReal *pfQuadratic, dReal *pfRoots) |
|
template<class T > |
T | RAD_2_DEG (T radians) |
|
float | RaveAcos (float f) |
|
double | RaveAcos (double f) |
|
float | RaveCos (float f) |
|
double | RaveCos (double f) |
|
float | RaveFabs (float f) |
|
double | RaveFabs (double f) |
|
float | RaveSin (float f) |
|
double | RaveSin (double f) |
|
float | RaveSqrt (float f) |
|
double | RaveSqrt (double f) |
|
bool | RayOBBTest (const RAY &r, const OBB &obb) |
|
template<class T > |
int | solvequad (T a, T b, T c, T &r1, T &r2) |
|
template<class T > |
void | sub (T *pf1, T *pf2, int r) |
|
template<class T > |
T | sum (T *pf, int length) |
|
void | svd3 (const dReal *A, dReal *U, dReal *D, dReal *V) |
|
dReal * | transcoord3 (dReal *pfout, const TransformMatrix *pmat, const dReal *pf) |
| computes (*pmat) * v More...
|
|
template<class T > |
T * | transcoord3 (T *pfout, const RaveTransformMatrix< T > *pmat, const T *pf) |
|
float * | transnorm3 (float *pfout, const float *pfmat, const float *pf) |
|
double * | transnorm3 (double *pfout, const double *pfmat, const double *pf) |
|
dReal * | transnorm3 (dReal *pfout, const TransformMatrix *pmat, const dReal *pf) |
| uses only 3x3 upper submatrix More...
|
|
template<class T > |
T * | transnorm3 (T *pfout, const RaveTransformMatrix< T > *pmat, const T *pf) |
|
float * | transpose3 (const float *pf, float *pfres) |
|
double * | transpose3 (const double *pf, double *pfres) |
|
float * | transpose4 (const float *pf, float *pfres) |
|
double * | transpose4 (const double *pf, double *pfres) |
|
template<class T , class S > |
void | Tridiagonal3 (S *mat, T *diag, T *subd) |
|
bool | TriTriCollision (const RaveVector< float > &u1, const RaveVector< float > &u2, const RaveVector< float > &u3, const RaveVector< float > &v1, const RaveVector< float > &v2, const RaveVector< float > &v3, RaveVector< float > &contactpos, RaveVector< float > &contactnorm) |
|
bool | TriTriCollision (const RaveVector< double > &u1, const RaveVector< double > &u2, const RaveVector< double > &u3, const RaveVector< double > &v1, const RaveVector< double > &v2, const RaveVector< double > &v3, RaveVector< double > &contactpos, RaveVector< double > &contactnorm) |
|