Go to the source code of this file.
Classes | |
struct | Mat3d |
Data structure for the representation of a 3x3 matrix. More... | |
struct | Quaternion |
Data structure for the representation of a quaternion. More... | |
struct | Transformation3d |
Data structure for the representation of a 3D rigid body transformation. More... | |
struct | Vec3d |
Data structure for the representation of a 3D vector. More... | |
Namespaces | |
namespace | Math3d |
Efficient mathematic functions operating on the data types Vec3d, Mat3d, Transformation3d, and Quaternion. | |
Typedefs | |
typedef CDynamicArrayTemplate < Vec3d > | CVec3dArray |
typedef std::vector< Vec3d > | Vec3dList |
Functions | |
void | Math3d::AddMatMat (const Mat3d &matrix1, const Mat3d &matrix2, Mat3d &matrix) |
void | Math3d::AddToMat (Mat3d &matrix, const Mat3d &matrixToAdd) |
void | Math3d::AddToVec (Vec3d &vec, const Vec3d &vectorToAdd) |
void | Math3d::AddVecVec (const Vec3d &vector1, const Vec3d &vector2, Vec3d &result) |
float | Math3d::Angle (const Vec3d &vector1, const Vec3d &vector2) |
float | Math3d::Angle (const Vec3d &vector1, const Vec3d &vector2, const Vec3d &axis) |
void | Math3d::Average (const Vec3d &vector1, const Vec3d &vector2, Vec3d &result) |
void | Math3d::CrossProduct (const Vec3d &vector1, const Vec3d &vector2, Vec3d &result) |
float | Math3d::Det (const Mat3d &matrix) |
float | Math3d::Distance (const Vec3d &vector1, const Vec3d &vector2) |
float | Math3d::EvaluateForm (const Vec3d &matrix1, const Mat3d &matrix2) |
void | Math3d::GetAxisAndAngle (const Mat3d &R, Vec3d &axis, float &angle) |
void | Math3d::Invert (const Mat3d &matrix, Mat3d &result) |
void | Math3d::Invert (const Transformation3d &input, Transformation3d &result) |
float | Math3d::Length (const Vec3d &vec) |
bool | Math3d::LoadFromFile (Vec3d &vector, const char *pFilePath) |
bool | Math3d::LoadFromFile (Mat3d &matrix, const char *pFilePath) |
bool | Math3d::LoadFromFile (Transformation3d &transformation, const char *pFilePath) |
void | Math3d::Mean (const CVec3dArray &vectorList, Vec3d &result) |
void | Math3d::Mean (const Vec3d *pVectors, int nVectors, Vec3d &result) |
void | Math3d::MulMatMat (const Mat3d &matrix1, const Mat3d &matrix2, Mat3d &result) |
void | Math3d::MulMatScalar (const Mat3d &matrix, float scalar, Mat3d &result) |
void | Math3d::MulMatVec (const Mat3d &matrix, const Vec3d &vec, Vec3d &result) |
void | Math3d::MulMatVec (const Mat3d &matrix, const Vec3d &vector1, const Vec3d &vector2, Vec3d &result) |
void | Math3d::MulQuatQuat (const Quaternion &quat1, const Quaternion &quat2, Quaternion &result) |
void | Math3d::MulTransTrans (const Transformation3d &transformation1, const Transformation3d &transformation2, Transformation3d &result) |
void | Math3d::MulTransVec (const Transformation3d &transformation, const Vec3d &vec, Vec3d &result) |
void | Math3d::MulVecScalar (const Vec3d &vec, float scalar, Vec3d &result) |
void | Math3d::MulVecTransposedVec (const Vec3d &vector1, const Vec3d &vector2, Mat3d &result) |
void | Math3d::NormalizeVec (Vec3d &vec) |
void | Math3d::RotateVec (const Vec3d &vec, const Vec3d &rotation, Vec3d &result) |
void | Math3d::RotateVecAngleAxis (const Vec3d &vec, const Vec3d &axis, float theta, Vec3d &result) |
void | Math3d::RotateVecQuaternion (const Vec3d &vec, const Vec3d &axis, float theta, Vec3d &result) |
void | Math3d::RotateVecYZX (const Vec3d &vec, const Vec3d &rotation, Vec3d &result) |
bool | Math3d::SaveToFile (const Vec3d &vector, const char *pFilePath) |
bool | Math3d::SaveToFile (const Mat3d &matrix, const char *pFilePath) |
bool | Math3d::SaveToFile (const Transformation3d &transformation, const char *pFilePath) |
float | Math3d::ScalarProduct (const Vec3d &vector1, const Vec3d &vector2) |
void | Math3d::SetMat (Mat3d &matrix, float r1, float r2, float r3, float r4, float r5, float r6, float r7, float r8, float r9) |
void | Math3d::SetMat (Mat3d &matrix, const Mat3d &sourceMatrix) |
void | Math3d::SetRotationMat (Mat3d &matrix, const Vec3d &axis, float theta) |
void | Math3d::SetRotationMat (Mat3d &matrix, float alpha, float beta, float gamma) |
void | Math3d::SetRotationMat (Mat3d &matrix, const Vec3d &rotation) |
void | Math3d::SetRotationMatAxis (Mat3d &matrix, const Vec3d &axis, float theta) |
void | Math3d::SetRotationMatX (Mat3d &matrix, float theta) |
void | Math3d::SetRotationMatY (Mat3d &matrix, float theta) |
void | Math3d::SetRotationMatYZX (Mat3d &matrix, const Vec3d &rotation) |
void | Math3d::SetRotationMatZ (Mat3d &matrix, float theta) |
void | Math3d::SetTransformation (Transformation3d &transformation, const Vec3d &rotation, const Vec3d &translation) |
void | Math3d::SetTransformation (Transformation3d &transformation, const Transformation3d &sourceTransformation) |
void | Math3d::SetVec (Vec3d &vec, float x, float y, float z) |
void | Math3d::SetVec (Vec3d &vec, const Vec3d &sourceVector) |
float | Math3d::SquaredDistance (const Vec3d &vector1, const Vec3d &vector2) |
float | Math3d::SquaredLength (const Vec3d &vec) |
void | Math3d::SubtractFromVec (Vec3d &vec, const Vec3d &vectorToSubtract) |
void | Math3d::SubtractMatMat (const Mat3d &matrix1, const Mat3d &matrix2, Mat3d &result) |
void | Math3d::SubtractVecVec (const Vec3d &vector1, const Vec3d &vector2, Vec3d &result) |
void | Math3d::TransformVec (const Vec3d &vec, const Vec3d &rotation, const Vec3d &translation, Vec3d &result) |
void | Math3d::TransformVecYZX (const Vec3d &vec, const Vec3d &rotation, const Vec3d &translation, Vec3d &result) |
void | Math3d::Transpose (const Mat3d &matrix, Mat3d &result) |
Variables | |
const Mat3d | Math3d::unit_mat = { 1, 0, 0, 0, 1, 0, 0, 0, 1 } |
const Mat3d | Math3d::zero_mat = { 0, 0, 0, 0, 0, 0, 0, 0 ,0 } |
const Vec3d | Math3d::zero_vec = { 0, 0, 0 } |
typedef CDynamicArrayTemplate<Vec3d> CVec3dArray |