AUTh-ARL Core Stack
0.7
|
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... | |
Math related to robotics calculations.
arma::mat arl::robot::trajectory::get3rdOrder | ( | double | t, |
arma::vec | p0, | ||
arma::vec | pT, | ||
double | totalTime | ||
) |
Designs a 3th order trajectory.
t | For the current time instance |
p0 | From this point (initial) |
pT | To the target |
totalTime | If the total duaration of motion is this |
arma::mat arl::robot::trajectory::get5thOrder | ( | double | t, |
arma::vec | p0, | ||
arma::vec | pT, | ||
double | totalTime | ||
) |
Designs a 5th order trajectory.
t | For the current time instance |
p0 | From this point (initial) |
pT | To the target |
totalTime | If the total duaration of motion is this |
arma::mat arl::robot::trajectory::get5thOrderRotationMatrix | ( | double | t, |
arma::mat | R0, | ||
arma::mat | Rt, | ||
double | totalTime | ||
) |
Designs a 5th order trajectory for orientation.
t | For the current time instance |
R0 | Initial orientation |
Rt | Target orientation |
totalTime | If the total duration of motion is this |
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.
rotation | The given 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.
state | The current state. A matrix with 3 columns for position, velocity and acceleration |
goal | The goal state |
tau | The time until we reach the goal |
dt | The 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.
homogen | The homogeneous transformation |
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.
jac | The full jacobian matrix of the arm |
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.
jac | The full jacobian matrix of the arm |
choose | A matrix for choosing a specific row of the jacobian (e.g. if you need only the manipulability in the z-axis (3rd row) |
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:
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.
homogen | The homogeneous transformation between the two frames |
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:
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.
homogen | The homogeneous transformation between the two frames |
|
inline |
Calculates the pseudoinverse of a matrix.
tolerance | Any singular values less than tolerance are treated as zero. The default value is the machine precision given by NumTraits<Scalar>::epsilon() |
,
|
inline |
|
inline |
Calculates the skew symmetrix given a 3D vector using KDL.
v | A KDL vector |
skew | A KDL rotation matrix as output |
|
inline |
Calculates the skew symmetrix given a 3D vector using Eigen.
|
inline |
Calculates the skew symmetrix given a 3D vector using Armadillo.
v | An arma 3D vector |
skew | An arma 3x3 matrix as output |