modern_robotics
|
Functions | |
const arma::mat | mr::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 | mr::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 | mr::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 | mr::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 | mr::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 > | mr::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 > | mr::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 > | mr::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 > > | mr::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::vec mr::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.
thetalist | A list of joint variables |
Ftip | Spatial force applied by the end-effector expressed in frame {n+1} |
Mlist | List of link frames i relative to i-1 at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns |
const std::tuple< const arma::vec, const arma::vec > mr::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.
thetalist | n-vector of joint variables |
dthetalist | n-vector of joint rates |
ddthetalist | n-vector of joint accelerations |
dt | The timestep delta t |
const arma::vec mr::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.
thetalist | A list of joint variables |
dthetalist | A list of joint rates |
taulist | An n-vector of joint forces/torques |
g | Gravity vector g |
Ftip | Spatial force applied by the end-effector expressed in frame {n+1} |
Mlist | List of link frames i relative to i-1 at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns |
This function computes ddthetalist by solving: Mlist(thetalist) * ddthetalist = taulist - c(thetalist,dthetalist) - g(thetalist) - Jtr(thetalist) * Ftip
const std::tuple< const std::vector< arma::vec >, const std::vector< arma::vec > > mr::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.
thetalist | n-vector of initial joint variables |
dthetalist | n-vector of initial joint rates |
taumat | An N x n matrix of joint forces/torques, where each row is the joint effort at any time step |
g | Gravity vector g |
Ftipmat | An N x 6 matrix of spatial forces applied by the end- effector (If there are no tip forces the user should input a zero and a zero matrix will be used) |
Mlist | List of link frames {i} relative to {i-1} at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns |
dt | The timestep between consecutive joint forces/torques |
intRes | Integration resolution is the number of times integration (Euler) takes places between each time step. Must be an integer value greater than or equal to 1 |
This function calls a numerical integration procedure that uses ForwardDynamics.
const arma::vec mr::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.
thetalist | A list of joint variables |
g | 3-vector for gravitational acceleration |
Mlist | List of link frames i relative to i-1 at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns |
This function calls InverseDynamics with Ftip = 0, dthetalist = 0, and ddthetalist = 0.
const std::vector< arma::vec > mr::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.
thetamat | An N x n matrix of robot joint variables |
dthetamat | An N x n matrix of robot joint velocities |
ddthetamat | An N x n matrix of robot joint accelerations |
g | Gravity vector g |
Ftipmat | An N x 6 matrix of spatial forces applied by the end- effector (If there are no tip forces the user should input a zero and a zero matrix will be used) |
Mlist | List of link frames i relative to i-1 at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns |
const arma::mat mr::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.
thetalist | A list of joint variables |
Mlist | List of link frames i relative to i-1 at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns |
This function calls InverseDynamics n times, each time passing a ddthetalist vector with a single element equal to one and all other inputs set to zero. Each call of InverseDynamics generates a single column, and these columns are assembled to create the inertia matrix.
const std::tuple< const arma::vec, const arma::vec > mr::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.
thetalist | n-vector of joint variables |
dthetalist | n-vector of joint rates |
f | function that calculate the ddthetalist |
dt | The timestep delta t |
const arma::vec mr::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.
thetalist | A list of joint variables |
dthetalist | A list of joint rates |
Mlist | List of link frames i relative to i-1 at the home position |
Glist | Spatial inertia matrices Gi of the links |
Slist | Screw axes Si of the joints in a space frame, in the format of a matrix with axes as the columns. |
This function calls InverseDynamics with g = 0, Ftip = 0, and ddthetalist = 0.