Mathematical functions. More...
#include <vecmath.h>
Static Public Member Functions | |
| static void | calcAngles (double leg1, double leg2, double x, double y, double &first, double &second) |
| Calculates inverse kinematics of a standard two link leg. More... | |
| static double | calcDotProduct (double firstVector[], double secondVector[], int size) |
| Calculates dot product of two double vectors of the stated size. More... | |
| static void | calcMatrixResult (double matrix[], double vector[], int rows, int columns, double resultVector[]) |
| Calculates vector-matrix product. More... | |
| static void | getEulerZXZ (CMatrix &mat, CVec &first) |
| Transforms homogenous matrix into Euler angle (YZX) representation (two solutions) More... | |
| static void | getMatrixFromRotation (CMatrix &mat, const CVec &axis, double angle) |
| Transforms axis-angle representation into homogenous matrix representation. More... | |
| static void | getOrientation (CMatrix &mat, CVec &first, CVec &second, bool old=false) |
| Transforms homogenous matrix into Euler angle (YZX) representation (two solutions) More... | |
| static void | getQuaternionFromRotation (CVec &quater, CVec &axis, double angle) |
| static void | getRotation (CMatrix &mat, CVec &vec, bool old=false) |
| ransforms Euler angle (YZX) representation into homogenous matrix representation More... | |
| static void | getRotation (CMatrix &mat, double x, double y, double z, bool old=false) |
| Transforms Euler angle (YZX) representation into homogenous matrix representation. More... | |
| static void | getRotationFromMatrix (const CMatrix &mat, CVec &axis, double &angle) |
| Transforms homogenous matrix into axis-angle representation. More... | |
| static void | matrixFromQuaternion (CVec &quaternion, CMatrix &matrix) |
| Transforms a quaternion into homogenous matrix representation. More... | |
| static void | multiplyMatrices (double *firstMatrix, double *secondMatrix, int firstRows, int firstColumns, int secondColumns, double *resultMatrix) |
| Multiplies two matrices. More... | |
| static void | quaternionFromMatrix (const CMatrix &mat, CVec &quaternion) |
| Transforms a homogenous matrix into quaternion representation. More... | |
| static void | transposeMatrix (double *matrix, double *resultMatrix, int size) |
| Transposes a matrix. More... | |
|
static |
Calculates inverse kinematics of a standard two link leg.
| leg1 | Length of leg connected to base |
| leg2 | Length of leg connected to hand |
| x | Cartesian x position of hand |
| y | Cartesian y position of hand |
| first | Angle between base and leg1 |
| second | Angle between leg1 and leg2 (elbow) |
Definition at line 756 of file vecmath.cpp.
|
static |
Calculates dot product of two double vectors of the stated size.
Definition at line 511 of file vecmath.cpp.
|
static |
Calculates vector-matrix product.
| resultVector | Has to be allocated |
Definition at line 499 of file vecmath.cpp.
Transforms homogenous matrix into Euler angle (YZX) representation (two solutions)
Definition at line 618 of file vecmath.cpp.
|
static |
Transforms axis-angle representation into homogenous matrix representation.
Definition at line 409 of file vecmath.cpp.
|
static |
Transforms homogenous matrix into Euler angle (YZX) representation (two solutions)
Definition at line 642 of file vecmath.cpp.
|
static |
Definition at line 436 of file vecmath.cpp.
ransforms Euler angle (YZX) representation into homogenous matrix representation
Definition at line 750 of file vecmath.cpp.
|
static |
Transforms Euler angle (YZX) representation into homogenous matrix representation.
Definition at line 692 of file vecmath.cpp.
|
static |
Transforms homogenous matrix into axis-angle representation.
Definition at line 463 of file vecmath.cpp.
Transforms a quaternion into homogenous matrix representation.
Definition at line 372 of file vecmath.cpp.
|
static |
Multiplies two matrices.
| resultMatrix | Has to be allocated |
Definition at line 579 of file vecmath.cpp.
Transforms a homogenous matrix into quaternion representation.
| quaternion | XYZ is the rotation axis part, W the angle part |
Definition at line 525 of file vecmath.cpp.
|
static |
Transposes a matrix.
Set resultMatrix to matrix if you want to transpose the matrix
| resultMatrix | Has to be allocated |
Definition at line 565 of file vecmath.cpp.