AUTh-ARL Core Stack  0.7
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
Math/Robotics

Math related to robotics calculations. More...

Classes

class  arl::primitive::JointTrajectory
 Stores a Robot Joint Trajectory, providing interfaces with Armadillo or ROS msgs. You can provide the class with several points and it will interpolate returning position, velocity, acceleration in any given time. More...
 
class  arl::primitive::Trajectory< T >
 Represent a simple fifth order polynomial trajectory. Its a templated class that can be used with multiple types. More...
 
class  arl::math::Admittance
 Integrates the dynamical system for admittance control. More...
 
class  arl::math::Clik
 Calculates joint velocities given desired task velocities by implementing Closed Loop Inverse Kinematics. More...
 

Functions

EIGEN_DEVICE_FUNC Matrix
< Scalar, 3, 3 > 
skewSymmetric () const
 Returns the skew symmetric matrix from an Eigen Vector. More...
 
EIGEN_DEVICE_FUNC Matrix
< Scalar, internal::traits
< Derived >::ColsAtCompileTime,
internal::traits< Derived >
::RowsAtCompileTime > 
pinv (Scalar tolerance=Scalar{NumTraits< Scalar >::epsilon()}) const
 Calculates the pseudoinverse of a matrix. More...
 
double arl::math::getTranslationalManipulabilityMeasureStrongSense (const arma::mat &jac)
 Calculates the translational manipulability measure in the strong sense as this is defined in Yoshikawa, Tsuneo. "Translational and rotational manipulability of robotic manipulators." American Control Conference, 1990. IEEE, 1990. APA. More...
 
double arl::math::getTranslationalManipulabilityMeasureStrongSense (const arma::mat &jac, const arma::mat &choose)
 Calculates the translational manipulability measure in the strong sense as this is defined in Yoshikawa, Tsuneo. "Translational and rotational manipulability of robotic manipulators." American Control Conference, 1990. IEEE, 1990. APA. More...
 
arma::mat arl::math::getScrewTransformation (const arma::mat &homogen)
 Returns the screw transformation. More...
 
arma::mat arl::math::getTwistTransformation (const arma::mat &homogen)
 Calculates the twist transformation as defined in Eq. (4.23) p. 117 [2] using Armadillo. More...
 
Eigen::Matrix6d arl::math::getTwistTransformation (const Eigen::Affine3d &transformation)
 Calculates the twist transformation as defined in Eq. (4.23) p. 117 [2] using Eigen. More...
 
arma::mat arl::math::get6x6Rotation (const arma::mat &rotation)
 Returns the 6x6 matrix which the upper left and the down right sumbmatrices are the given 3x3 rotation matrix. More...
 
void arl::math::skewSymmetric (const KDL::Vector &v, KDL::Rotation *skew)
 Calculates the skew symmetrix given a 3D vector using KDL. More...
 
void arl::math::skewSymmetric (const Eigen::Matrix< double, 3, 1 > &v, Eigen::Matrix< double, 3, 3 > *skew)
 Calculates the skew symmetrix given a 3D vector using Eigen. More...
 
void arl::math::skewSymmetric (const arma::vec &v, arma::mat *skew)
 Calculates the skew symmetrix given a 3D vector using Armadillo. More...
 
arma::mat arl::robot::trajectory::get5thOrder (double t, arma::vec p0, arma::vec pT, double totalTime)
 Designs a 5th order trajectory. More...
 
arma::mat arl::robot::trajectory::get5thOrderRotationMatrix (double t, arma::mat R0, arma::mat Rt, double totalTime)
 Designs a 5th order trajectory for orientation. More...
 
arma::mat arl::robot::trajectory::get3rdOrder (double t, arma::vec p0, arma::vec pT, double totalTime)
 Designs a 3th order trajectory. More...
 
arma::mat arl::robot::trajectory::getMinJerk (const arma::mat &state, const arma::vec &goal, double tau, double dt)
 Computes minimum jerk trajectory step given that we are currently in x, xd, xdd and that we have tau time before we reach the goal. More...
 

Detailed Description

Math related to robotics calculations.

Function Documentation

arma::mat arl::robot::trajectory::get3rdOrder ( double  t,
arma::vec  p0,
arma::vec  pT,
double  totalTime 
)

Designs a 3th order trajectory.

Parameters
tFor the current time instance
p0From this point (initial)
pTTo the target
totalTimeIf the total duaration of motion is this
Returns
The exact position, velocity and acceleration for that time instance, as columns [p][pdot][pddot]
arma::mat arl::robot::trajectory::get5thOrder ( double  t,
arma::vec  p0,
arma::vec  pT,
double  totalTime 
)

Designs a 5th order trajectory.

Parameters
tFor the current time instance
p0From this point (initial)
pTTo the target
totalTimeIf the total duaration of motion is this
Returns
The exact position, velocity and acceleration for that time instance, as columns [p][pdot][pddot]
arma::mat arl::robot::trajectory::get5thOrderRotationMatrix ( double  t,
arma::mat  R0,
arma::mat  Rt,
double  totalTime 
)

Designs a 5th order trajectory for orientation.

Parameters
tFor the current time instance
R0Initial orientation
RtTarget orientation
totalTimeIf the total duration of motion is this
Returns
The exact orientation[3x3], angular velocity[3x1] and angular acceleration[3x1] for that time instance, as columns [R][qdot][qddot]

Here is the call graph for this function:

arma::mat arl::math::get6x6Rotation ( const arma::mat &  rotation)

Returns the 6x6 matrix which the upper left and the down right sumbmatrices are the given 3x3 rotation matrix.

Parameters
rotationThe given rotation matrix
Returns
The 6x6 rotation matrix
arma::mat arl::robot::trajectory::getMinJerk ( const arma::mat &  state,
const arma::vec &  goal,
double  tau,
double  dt 
)

Computes minimum jerk trajectory step given that we are currently in x, xd, xdd and that we have tau time before we reach the goal.

Parameters
stateThe current state. A matrix with 3 columns for position, velocity and acceleration
goalThe goal state
tauThe time until we reach the goal
dtThe time step
arma::mat arl::math::getScrewTransformation ( const arma::mat &  homogen)

Returns the screw transformation.

The screw transformation (gamma matrix) for transforming a wrench applied on frame {B} and expressed in frame {B} to the wrench applied on frame {A} and expressed in frame {A}, as given in given by 4.27 in Doulgeri Robotics. The calculation is based on a 3x4 matrix storing the homogeneous transformation from tranferring something expressed in frame {B} to something expressed in frame {A}. The first three columns should contain the rotation matrix and the last column the translation.

Parameters
homogenThe homogeneous transformation
Returns
The screw transformation matrix

Here is the call graph for this function:

double arl::math::getTranslationalManipulabilityMeasureStrongSense ( const arma::mat &  jac)

Calculates the translational manipulability measure in the strong sense as this is defined in Yoshikawa, Tsuneo. "Translational and rotational manipulability of robotic manipulators." American Control Conference, 1990. IEEE, 1990. APA.

Parameters
jacThe full jacobian matrix of the arm
Returns
The TMM in the strong sense
double arl::math::getTranslationalManipulabilityMeasureStrongSense ( const arma::mat &  jac,
const arma::mat &  choose 
)

Calculates the translational manipulability measure in the strong sense as this is defined in Yoshikawa, Tsuneo. "Translational and rotational manipulability of robotic manipulators." American Control Conference, 1990. IEEE, 1990. APA.

Parameters
jacThe full jacobian matrix of the arm
chooseA matrix for choosing a specific row of the jacobian (e.g. if you need only the manipulability in the z-axis (3rd row)
Returns
The TMM in the strong sense
arma::mat arl::math::getTwistTransformation ( const arma::mat &  homogen)

Calculates the twist transformation as defined in Eq. (4.23) p. 117 [2] using Armadillo.

Returns the matrix:

$\Gamma_{bc} = \begin{bmatrix}R_{bc} & \hat{p}_{bc}R_{bc} \\ 0 & R_{bc}\end{bmatrix}$

where the rotation and the translation are taken from the given homogeneous matrix.

If you want to transfer a twist from frame c to frame b you can do it by multiplying the output with the twist from the right.

Parameters
homogenThe homogeneous transformation between the two frames
Returns
The twist transformation

Here is the call graph for this function:

Eigen::Matrix6d arl::math::getTwistTransformation ( const Eigen::Affine3d &  transformation)

Calculates the twist transformation as defined in Eq. (4.23) p. 117 [2] using Eigen.

Returns the matrix:

$\Gamma_{bc} = \begin{bmatrix}R_{bc} & \hat{p}_{bc}R_{bc} \\ 0 & R_{bc}\end{bmatrix}$

where the rotation and the translation are taken from the given homogeneous matrix.

If you want to transfer a twist from frame c to frame b you can do it by multiplying the output with the twist from the right.

Parameters
homogenThe homogeneous transformation between the two frames
Returns
The twist transformation
EIGEN_DEVICE_FUNC Matrix<Scalar, internal::traits<Derived>::ColsAtCompileTime, internal::traits<Derived>::RowsAtCompileTime> pinv ( Scalar  tolerance = Scalar{NumTraits<Scalar>::epsilon()}) const
inline

Calculates the pseudoinverse of a matrix.

Parameters
toleranceAny singular values less than tolerance are treated as zero. The default value is the machine precision given by NumTraits<Scalar>::epsilon()
Returns
The pseudoinverse matrix.

,

EIGEN_DEVICE_FUNC Matrix<Scalar, 3, 3> skewSymmetric ( ) const
inline

Returns the skew symmetric matrix from an Eigen Vector.

Returns
The 3x3 skew symmetric matrix

,

void arl::math::skewSymmetric ( const KDL::Vector &  v,
KDL::Rotation *  skew 
)
inline

Calculates the skew symmetrix given a 3D vector using KDL.

Parameters
vA KDL vector
skewA KDL rotation matrix as output
Deprecated:
Use EIGEN_DEVICE_FUNC inline Matrix<Scalar, 3, 3> skewSymmetric() const instead.
void arl::math::skewSymmetric ( const Eigen::Matrix< double, 3, 1 > &  v,
Eigen::Matrix< double, 3, 3 > *  skew 
)
inline

Calculates the skew symmetrix given a 3D vector using Eigen.

Parameters
vAn Eigen 3D vector
skewAn Eigen 3x3 matrix as output
Deprecated:
Use EIGEN_DEVICE_FUNC inline Matrix<Scalar, 3, 3> skewSymmetric() const instead.
void arl::math::skewSymmetric ( const arma::vec &  v,
arma::mat *  skew 
)
inline

Calculates the skew symmetrix given a 3D vector using Armadillo.

Parameters
vAn arma 3D vector
skewAn arma 3x3 matrix as output
Deprecated:
Use EIGEN_DEVICE_FUNC inline Matrix<Scalar, 3, 3> skewSymmetric() const instead.