Static Public Member Functions
robotLibPbD::CMathLib Class Reference

Mathematical functions. More...

#include <vecmath.h>

List of all members.

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.
static double calcDotProduct (double firstVector[], double secondVector[], int size)
 Calculates dot product of two double vectors of the stated size.
static void calcMatrixResult (double matrix[], double vector[], int rows, int columns, double resultVector[])
 Calculates vector-matrix product.
static void getEulerZXZ (CMatrix &mat, CVec &first)
 Transforms homogenous matrix into Euler angle (YZX) representation (two solutions)
static void getMatrixFromRotation (CMatrix &mat, const CVec &axis, double angle)
 Transforms axis-angle representation into homogenous matrix representation.
static void getOrientation (CMatrix &mat, CVec &first, CVec &second, bool old=false)
 Transforms homogenous matrix into Euler angle (YZX) representation (two solutions)
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
static void getRotation (CMatrix &mat, double x, double y, double z, bool old=false)
 Transforms Euler angle (YZX) representation into homogenous matrix representation.
static void getRotationFromMatrix (const CMatrix &mat, CVec &axis, double &angle)
 Transforms homogenous matrix into axis-angle representation.
static void matrixFromQuaternion (CVec &quaternion, CMatrix &matrix)
 Transforms a quaternion into homogenous matrix representation.
static void multiplyMatrices (double *firstMatrix, double *secondMatrix, int firstRows, int firstColumns, int secondColumns, double *resultMatrix)
 Multiplies two matrices.
static void quaternionFromMatrix (const CMatrix &mat, CVec &quaternion)
 Transforms a homogenous matrix into quaternion representation.
static void transposeMatrix (double *matrix, double *resultMatrix, int size)
 Transposes a matrix.

Detailed Description

Mathematical functions.

Definition at line 275 of file vecmath.h.


Member Function Documentation

void robotLibPbD::CMathLib::calcAngles ( double  leg1,
double  leg2,
double  x,
double  y,
double &  first,
double &  second 
) [static]

Calculates inverse kinematics of a standard two link leg.

Parameters:
leg1Length of leg connected to base
leg2Length of leg connected to hand
xCartesian x position of hand
yCartesian y position of hand
firstAngle between base and leg1
secondAngle between leg1 and leg2 (elbow)

Definition at line 756 of file vecmath.cpp.

double robotLibPbD::CMathLib::calcDotProduct ( double  firstVector[],
double  secondVector[],
int  size 
) [static]

Calculates dot product of two double vectors of the stated size.

Definition at line 511 of file vecmath.cpp.

void robotLibPbD::CMathLib::calcMatrixResult ( double  matrix[],
double  vector[],
int  rows,
int  columns,
double  resultVector[] 
) [static]

Calculates vector-matrix product.

Parameters:
resultVectorHas to be allocated

Definition at line 499 of file vecmath.cpp.

void robotLibPbD::CMathLib::getEulerZXZ ( CMatrix mat,
CVec first 
) [static]

Transforms homogenous matrix into Euler angle (YZX) representation (two solutions)

Definition at line 618 of file vecmath.cpp.

void robotLibPbD::CMathLib::getMatrixFromRotation ( CMatrix mat,
const CVec axis,
double  angle 
) [static]

Transforms axis-angle representation into homogenous matrix representation.

Definition at line 409 of file vecmath.cpp.

void robotLibPbD::CMathLib::getOrientation ( CMatrix mat,
CVec first,
CVec second,
bool  old = false 
) [static]

Transforms homogenous matrix into Euler angle (YZX) representation (two solutions)

Definition at line 642 of file vecmath.cpp.

void robotLibPbD::CMathLib::getQuaternionFromRotation ( CVec quater,
CVec axis,
double  angle 
) [static]

Definition at line 436 of file vecmath.cpp.

void robotLibPbD::CMathLib::getRotation ( CMatrix mat,
CVec vec,
bool  old = false 
) [static]

ransforms Euler angle (YZX) representation into homogenous matrix representation

See also:
getRotation

Definition at line 750 of file vecmath.cpp.

void robotLibPbD::CMathLib::getRotation ( CMatrix mat,
double  x,
double  y,
double  z,
bool  old = false 
) [static]

Transforms Euler angle (YZX) representation into homogenous matrix representation.

Definition at line 692 of file vecmath.cpp.

void robotLibPbD::CMathLib::getRotationFromMatrix ( const CMatrix mat,
CVec axis,
double &  angle 
) [static]

Transforms homogenous matrix into axis-angle representation.

Definition at line 463 of file vecmath.cpp.

void robotLibPbD::CMathLib::matrixFromQuaternion ( CVec quaternion,
CMatrix matrix 
) [static]

Transforms a quaternion into homogenous matrix representation.

Definition at line 372 of file vecmath.cpp.

void robotLibPbD::CMathLib::multiplyMatrices ( double *  firstMatrix,
double *  secondMatrix,
int  firstRows,
int  firstColumns,
int  secondColumns,
double *  resultMatrix 
) [static]

Multiplies two matrices.

Parameters:
resultMatrixHas to be allocated

Definition at line 579 of file vecmath.cpp.

void robotLibPbD::CMathLib::quaternionFromMatrix ( const CMatrix mat,
CVec quaternion 
) [static]

Transforms a homogenous matrix into quaternion representation.

Parameters:
quaternionXYZ is the rotation axis part, W the angle part

Definition at line 525 of file vecmath.cpp.

void robotLibPbD::CMathLib::transposeMatrix ( double *  matrix,
double *  resultMatrix,
int  size 
) [static]

Transposes a matrix.

Set resultMatrix to matrix if you want to transpose the matrix

Parameters:
resultMatrixHas to be allocated

Definition at line 565 of file vecmath.cpp.


The documentation for this class was generated from the following files:


asr_kinematic_chain_optimizer
Author(s): Aumann Florian, Heller Florian, Jäkel Rainer, Wittenbeck Valerij
autogenerated on Sat Jun 8 2019 19:42:49