modern_robotics
Functions
Chapter 8: Dynamics of Open Chains

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...
 

Detailed Description

Function Documentation

◆ EndEffectorForces()

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.

Parameters
thetalistA list of joint variables
FtipSpatial force applied by the end-effector expressed in frame {n+1}
MlistList of link frames i relative to i-1 at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns
Returns
The joint forces and torques required only to create the end-effector force Ftip

◆ EulerStep()

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.

Parameters
thetalistn-vector of joint variables
dthetalistn-vector of joint rates
ddthetalistn-vector of joint accelerations
dtThe timestep delta t
Returns
thetalistNext: Vector of joint variables after dt from first order Euler integration
dthetalistNext: Vector of joint rates after dt from first order Euler integration

◆ ForwardDynamics()

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.

Parameters
thetalistA list of joint variables
dthetalistA list of joint rates
taulistAn n-vector of joint forces/torques
gGravity vector g
FtipSpatial force applied by the end-effector expressed in frame {n+1}
MlistList of link frames i relative to i-1 at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns
Returns
The resulting joint accelerations

This function computes ddthetalist by solving: Mlist(thetalist) * ddthetalist = taulist - c(thetalist,dthetalist) - g(thetalist) - Jtr(thetalist) * Ftip

◆ ForwardDynamicsTrajectory()

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.

Parameters
thetalistn-vector of initial joint variables
dthetalistn-vector of initial joint rates
taumatAn N x n matrix of joint forces/torques, where each row is the joint effort at any time step
gGravity vector g
FtipmatAn 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)
MlistList of link frames {i} relative to {i-1} at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns
dtThe timestep between consecutive joint forces/torques
intResIntegration 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
Returns
thetamat: The N x n matrix of robot joint angles resulting from the specified joint forces/torques
dthetamat: The N x n matrix of robot joint velocities

This function calls a numerical integration procedure that uses ForwardDynamics.

◆ GravityForces()

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.

Parameters
thetalistA list of joint variables
g3-vector for gravitational acceleration
MlistList of link frames i relative to i-1 at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns
Returns
The joint forces/torques required to overcome gravity at thetalist

This function calls InverseDynamics with Ftip = 0, dthetalist = 0, and ddthetalist = 0.

◆ InverseDynamicsTrajectory()

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.

Parameters
thetamatAn N x n matrix of robot joint variables
dthetamatAn N x n matrix of robot joint velocities
ddthetamatAn N x n matrix of robot joint accelerations
gGravity vector g
FtipmatAn 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)
MlistList of link frames i relative to i-1 at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns
Returns
The N x n matrix of joint forces/torques for the specified trajectory, where each of the N rows is the vector of joint forces/torques at each time step

◆ MassMatrix()

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.

Parameters
thetalistA list of joint variables
MlistList of link frames i relative to i-1 at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns
Returns
The numerical inertia matrix M(thetalist) of an n-joint serial chain at the given configuration thetalist

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.

◆ RK4Step()

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.

Parameters
thetalistn-vector of joint variables
dthetalistn-vector of joint rates
ffunction that calculate the ddthetalist
dtThe timestep delta t
Returns
thetalistNext: Vector of joint variables after dt from Runge–Kutta methods integration
dthetalistNext: Vector of joint rates after dt from Runge–Kutta methods integration

◆ VelQuandraticForces()

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.

Parameters
thetalistA list of joint variables
dthetalistA list of joint rates
MlistList of link frames i relative to i-1 at the home position
GlistSpatial inertia matrices Gi of the links
SlistScrew axes Si of the joints in a space frame, in the format of a matrix with axes as the columns.
Returns
The vector c(thetalist,dthetalist) of Coriolis and centripetal terms for a given thetalist and dthetalist.

This function calls InverseDynamics with g = 0, Ftip = 0, and ddthetalist = 0.