-
Notifications
You must be signed in to change notification settings - Fork 1
Dynamics APIs
Methods related to the Dynamics calculations are provided in this section. Note that some methods are for use in the serial systems (unconstrained), while others are specifically for use in the parallel (closed-loop) systems.
calc_M computes the joint space inertia matrix
calc_G computes the N by 1 gravity matrix
calc_InverseDynamics computes inverse dynamics using the Newton-Euler Algorithm
calc_ForwardDynamics computes forward dynamics with the Articulated Body Algorithm
calc_InverseDynamicsConstrained an inverse-dynamics operator that can be applied to fully-actuated constrained systems
calc_ForwardDynamicsConstrained computes forward dynamics with contact by constructing and solving the full lagrangian equation
calc_MInvTimesTau computes the effect of multiplying the inverse of the joint space inertia with the joint space torque vector
Computes the joint space inertia matrix by using the Composite Rigid Body Algorithm.
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
returns: MatrixNd M output inertia matrix
Computes the N x 1 gravity matrix of the dynamics model by equating the velocity and acceleration to zero. This method is specifically for open_loop manipulators. For closed-loop systems use InverseDynamicsConstrained method.
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
returns: VectorNd G computed gravity vector for each joint
Computes inverse dynamics with the Newton-Euler Algorithm (open-loop systems).
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
const VectorNd &QDot angular velocity vector of the internal joints
const VectorNd &QDDot angular acceleration vector of the internal joints
VectorNd &Tau actuations of the internal joints
returns: VectorNd &Tau computed torque for internal joints
Computes forward dynamics with the Articulated Body Algorithm (open-loop systems).
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
const VectorNd &QDot angular velocity vector of the internal joints
VectorNd &Tau actuations of the internal joints
const VectorNd &QDDot angular acceleration vector of the internal joints
returns: VectorNd &QDDot angular acceleration vector of the internal joints
calc_InverseDynamicsConstrained
An inverse-dynamics operator that can be applied to fully-actuated constrained systems.
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
const VectorNd &QDot angular velocity vector of the internal joints
const VectorNd &QDDotDesired N-element vector of desired generalized accelerations
ConstraintSet &CS model constraint set
const VectorNd &QDDotoutput N-element vector of generalized accelerations which satisfy the kinematic constraints
VectorNd &TauOutput N-element vector of generalized forces which satisfy the equations of motion for this constrained system
returns: VectorNd &TauOutput N-element vector of generalized forces which satisfy the equations of motion for this constrained system
calc_ForwardDynamicsConstrained
Computes forward dynamics with contact by constructing and solving the full lagrangian equation.
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
const VectorNd &QDot angular velocity vector of the internal joints
VectorNd &Tau actuations of the internal joints
ConstraintSet &CS model constraint set
const VectorNd &QDDotoutput N-element vector of generalized accelerations which satisfy the kinematic constraints
returns: const VectorNd &QDDotoutput N-element vector of generalized accelerations which satisfy the kinematic constraints
Computes the effect of multiplying the inverse of the joint space inertia matrix with a vector in linear time.
Specification:
input parameters:
const VectorNd &Q state vector of the internal joints
const VectorNd &Tau actuations of the internal joints
VectorNd &QDDot vector where the result will be stored
returns: VectorNd &QDDot` vector where the result will be stored
Creating a robot model in RBDL
Dynamics model test