|
const arma::mat66 | ad (const arma::vec6 &V) |
| Calculate the 6x6 matrix [adV] of the given 6-vector. More...
|
|
const arma::vec | InverseDynamics (const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &ddthetalist, const arma::vec &g, const arma::vec6 &Ftip, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
|
const arma::mat | MassMatrix (const arma::vec &thetalist, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
| Computes the mass matrix of an open chain robot based on the given configuration. More...
|
|
const arma::vec | VelQuandraticForces (const arma::vec &thetalist, const arma::vec &dthetalist, const std::vector< arma::mat44 > Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
| Computes the Coriolis and centripetal terms in the inverse dynamics of an open chain robot. More...
|
|
const arma::vec | GravityForces (const arma::vec &thetalist, const arma::vec3 &g, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
| Computes the joint forces/torques an open chain robot requires to overcome gravity at its configuration. More...
|
|
const arma::vec | EndEffectorForces (const arma::vec &thetalist, const arma::vec6 &Ftip, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
| Computes the joint forces/torques an open chain robot requires only to create the end-effector force Ftip. More...
|
|
const arma::vec | ForwardDynamics (const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &taulist, const arma::vec3 &g, const arma::vec6 &Ftip, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
| Computes forward dynamics in the space frame for an open chain robot. More...
|
|
const std::tuple< const arma::vec, const arma::vec > | EulerStep (const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &ddthetalist, const double dt) |
| Compute the joint angles and velocities at the next timestep using first order Euler integration. More...
|
|
const std::tuple< const arma::vec, const arma::vec > | RK4Step (const arma::vec &thetalist, const arma::vec &dthetalist, const std::function< const std::tuple< const arma::vec, const arma::vec >(const arma::vec &, const arma::vec &) > &f, const double dt) |
| Compute the joint angles and velocities at the next timestep using Runge–Kutta methods integration. More...
|
|
const std::vector< arma::vec > | InverseDynamicsTrajectory (const std::vector< arma::vec > &thetamat, const std::vector< arma::vec > &dthetamat, const std::vector< arma::vec > &ddthetamat, const arma::vec3 &g, const std::vector< arma::vec6 > &Ftipmat, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist) |
| Calculates the joint forces/torques required to move the serial chain along the given trajectory using inverse dynamics. More...
|
|
const std::tuple< const std::vector< arma::vec >, const std::vector< arma::vec > > | ForwardDynamicsTrajectory (const arma::vec &thetalist, const arma::vec &dthetalist, const std::vector< arma::vec > &taumat, const arma::vec3 &g, const std::vector< arma::vec6 > &Ftipmat, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const double dt, const int intRes) |
| Simulates the motion of a serial chain given an open-loop history of joint forces/torques. More...
|
|
const arma::mat44 | FKinBody (const arma::mat44 &M, const std::vector< arma::vec6 > &Blist, const arma::vec &thetalist) |
| Computes forward kinematics in the body frame for an open chain robot. More...
|
|
const arma::mat44 | FKinSpace (const arma::mat44 &M, const std::vector< arma::vec6 > &Slist, const arma::vec &thetalist) |
| Computes forward kinematics in the space frame for an open chain robot. More...
|
|
const std::pair< const arma::vec, bool > | IKinBody (const std::vector< arma::vec6 > &Blist, const arma::mat44 &M, const arma::mat44 &T, const arma::vec &thetalist0, const double emog, const double ev) |
| Computes inverse kinematics in the body frame for an open chain robot. More...
|
|
const std::pair< const arma::vec, bool > | IKinSpace (const std::vector< arma::vec6 > &Slist, const arma::mat44 &M, const arma::mat44 &T, const arma::vec &thetalist0, const double emog, const double ev) |
| Computes inverse kinematics in the space frame for an open chain robot. More...
|
|
const arma::mat33 | RotInv (const arma::mat33 &R) |
| Inverts a rotation matrix. More...
|
|
const arma::mat33 | VecToso3 (const arma::vec3 &omg) |
| Converts a 3-vector to an so(3) representation. More...
|
|
const arma::vec3 | so3ToVec (const arma::mat33 &so3mat) |
| Converts an so(3) representation to a 3-vector. More...
|
|
const std::tuple< const arma::vec3, double > | AxisAng3 (const arma::vec3 &expc3) |
| Converts a 3-vector of exponential coordinates for rotation into axis-angle form. More...
|
|
const arma::mat33 | MatrixExp3 (const arma::mat33 &so3mat) |
| Computes the matrix exponential of a matrix in so(3) More...
|
|
const arma::mat33 | MatrixLog3 (const arma::mat33 &R) |
| Computes the matrix logarithm of a rotation matrix. More...
|
|
const arma::mat44 | RpToTrans (const arma::mat33 &R, const arma::vec3 &p) |
| Converts a rotation matrix and a position vector into homogeneous transformation matrix. More...
|
|
const std::tuple< const arma::mat33, const arma::vec3 > | TransToRp (const arma::mat44 &T) |
| Converts a homogeneous transformation matrix into a rotation matrix and position vector. More...
|
|
const arma::mat44 | TransInv (const arma::mat44 &T) |
| Inverts a homogeneous transformation matrix. More...
|
|
const arma::mat44 | VecTose3 (const arma::vec6 &V) |
| Converts a spatial velocity vector into a 4x4 matrix in se3. More...
|
|
const arma::vec6 | se3ToVec (const arma::mat44 &se3mat) |
| Converts an se3 matrix into a spatial velocity vector. More...
|
|
const arma::mat66 | Adjoint (const arma::mat44 &T) |
| Computes the adjoint representation of a homogeneous transformation matrix. More...
|
|
const arma::vec6 | ScrewToAxis (const arma::vec3 &q, const arma::vec3 &s, const double h) |
| Takes a parametric description of a screw axis and converts it to a normalized screw axis. More...
|
|
const std::tuple< const arma::vec6, double > | AxisAng6 (const arma::vec6 &expc6) |
| Converts a 6-vector of exponential coordinates into screw axis-angle form. More...
|
|
const arma::mat44 | MatrixExp6 (const arma::mat44 &se3mat) |
| Computes the matrix exponential of an se3 representation of exponential coordinates. More...
|
|
const arma::mat44 | MatrixLog6 (const arma::mat44 &T) |
| Computes the matrix logarithm of a homogeneous transformation matrix. More...
|
|
const arma::mat33 | ProjectToSO3 (const arma::mat33 &mat) |
| Returns a projection of mat into SO(3) More...
|
|
const arma::mat44 | ProjectToSE3 (const arma::mat44 &mat) |
| Returns a projection of mat into SE(3) More...
|
|
double | DistanceToSO3 (const arma::mat33 &mat) |
| Returns the Frobenius norm to describe the distance of mat from the SO(3) manifold. More...
|
|
double | DistanceToSE3 (const arma::mat44 &mat) |
| Returns the Frobenius norm to describe the distance of mat from the SE(3) manifold. More...
|
|
bool | TestIfSO3 (const arma::mat33 &mat) |
| Returns true if mat is close to or on the manifold SO(3) More...
|
|
bool | TestIfSE3 (const arma::mat44 &mat) |
| Returns true if mat is close to or on the manifold SE(3) More...
|
|
const arma::vec | ComputeTorque (const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &eint, const arma::vec3 &g, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const arma::vec &thetalistd, const arma::vec &dthetalistd, const arma::vec &ddthetalistd, const double kp, const double ki, const double kd) |
| Computes the joint control torques at a particular time instant. More...
|
|
const std::tuple< std::vector< arma::vec >, std::vector< arma::vec > > | SimulateControl (const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec3 &g, const std::vector< arma::vec6 > &Ftipmat, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const std::vector< arma::vec > &thetamatd, const std::vector< arma::vec > &dthetamatd, const std::vector< arma::vec > &ddthetamatd, const arma::vec3 >ilde, const std::vector< arma::mat44 > &Mtildelist, const std::vector< arma::mat66 > &Gtildelist, const double kp, const double ki, const double kd, const double dt, const size_t intRes) |
| Simulates the computed torque controller over a given desired trajectory. More...
|
|
double | CubicTimeScaling (const double Tf, const double t) |
| Computes s(t) for a cubic time scaling. More...
|
|
double | QuinticTimeScaling (const double Tf, const double t) |
| Computes s(t) for a quintic time scaling. More...
|
|
const std::vector< arma::vec > | JointTrajectory (const arma::vec &thetastart, const arma::vec &thetaend, const double Tf, const size_t N, const Method &method) |
| Computes a straight-line trajectory in joint space. More...
|
|
const std::vector< arma::mat44 > | ScrewTrajectory (const arma::mat44 &Xstart, const arma::mat44 &Xend, const double Tf, const size_t N, const Method &method) |
| Computes a trajectory as a list of N SE(3) matrices corresponding to the screw motion about a space screw axis. More...
|
|
const std::vector< arma::mat44 > | CartesianTrajectory (const arma::mat44 &Xstart, const arma::mat44 &Xend, const double Tf, const size_t N, const Method &method) |
| Computes a trajectory as a list of N SE(3) matrices corresponding to the origin of the end-effector frame following a straight line. More...
|
|
constexpr bool | NearZero (const double z) |
| Check if a number is close to zero. More...
|
|
const arma::vec | Normalize (const arma::vec &vec) |
| Normalize a vector to unit length. More...
|
|
const arma::mat | JacobianBody (const std::vector< arma::vec6 > &Blist, const arma::vec &thetalist) |
| Computes the body Jacobian for an open chain robot. More...
|
|
const arma::mat | JacobianSpace (const std::vector< arma::vec6 > &Slist, const arma::vec &thetalist) |
| Computes the space Jacobian for an open chain robot. More...
|
|
const std::tuple< std::vector< arma::vec >, std::vector< arma::vec > > | SimulateControl (const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec3 &g, const std::vector< arma::vec6 > &Ftipmat, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const std::vector< arma::vec > &thetamatd, const std::vector< arma::vec > &dthetamatd, const std::vector< arma::vec > &ddthetamatd, const arma::vec3 >ilde, const std::vector< arma::mat44 > &Mtildelist, const std::vector< arma::mat66 > &Gtildelist, const double kp, const double ki, const double kd, const double dt, const unsigned int intRes) |
|