Main Content

forwardDynamics

Joint accelerations given joint torques and states

Description

jointAccel = forwardDynamics(robot) computes joint accelerations due to gravity at the robot home configuration, with zero joint velocities and no external forces.

jointAccel = forwardDynamics(robot,configuration) also specifies the joint positions of the robot configuration.

To specify the home configuration, zero joint velocities, or zero torques, use [] for that input argument.

jointAccel = forwardDynamics(robot,configuration,jointVel) also specifies the joint velocities of the robot.

jointAccel = forwardDynamics(robot,configuration,jointVel,jointTorq) also specifies the joint torques applied to the robot.

jointAccel = forwardDynamics(robot,configuration,jointVel,jointTorq,fext) also specifies an external force matrix that contains forces applied to each joint.

example

Examples

collapse all

Calculate the resultant joint accelerations for a given robot configuration with applied external forces and forces due to gravity. A wrench is applied to a specific body with the gravity being specified for the whole robot.

Load a KUKA iiwa 14 robot model from the Robotics System Toolbox™ loadrobot. The robot is specified as a rigidBodyTree object.

Set the data format to "row". For all dynamics calculations, the data format must be either "row" or "column".

Set the gravity. By default, gravity is assumed to be zero.

kukaIIWA14 = loadrobot("kukaIiwa14",DataFormat="row",Gravity=[0 0 -9.81]);

Get the home configuration for the kukaIIWA14 robot.

q = homeConfiguration(kukaIIWA14);

Specify the wrench vector that represents the external forces experienced by the robot. Use the externalForce function to generate the external force matrix. Specify the robot model, the end effector that experiences the wrench, the wrench vector, and the current robot configuration. wrench is given relative to the "iiwa_link_ee_kuka" body frame, which requires you to specify the robot configuration, q.

wrench = [0 0 0.5 0 0 0.3];
fext = externalForce(kukaIIWA14,"iiwa_link_ee_kuka",wrench,q);

Compute the resultant joint accelerations due to gravity, with the external force applied to the end-effector "iiwa_link_ee_kuka" when kukaIIWA14 is at its home configuration. The joint velocities and joint torques are assumed to be zero (input as an empty vector []).

qddot = forwardDynamics(kukaIIWA14,q,[],[],fext)
qddot = 1×7

   -0.0023   -0.0112    0.0036   -0.0212    0.0067   -0.0075  499.9920

Input Arguments

collapse all

Robot model, specified as a rigidBodyTree object. To use the forwardDynamics function, set the DataFormat property to either 'row' or 'column'.

Robot configuration, specified as a vector with positions for all nonfixed joints in the robot model. You can generate a configuration using homeConfiguration(robot), randomConfiguration(robot), or by specifying your own joint positions. To use the vector form of configuration, set the DataFormat property for the robot to either 'row' or 'column'.

Joint velocities, specified as a vector. The number of joint velocities is equal to the degrees of freedom of the robot. To use the vector form of jointVel, set the DataFormat property for the robot to either 'row' or 'column'.

Joint torques, specified as a vector. Each element corresponds to a torque applied to a specific joint. To use the vector form of jointTorq, set the DataFormat property for the robot to either 'row' or 'column'.

External force matrix, specified as either an n-by-6 or 6-by-n matrix, where n is the number of bodies of the robot. The shape depends on the DataFormat property of robot. The 'row' data format uses an n-by-6 matrix. The 'column' data format uses a 6-by-n.

The matrix lists only values other than zero at the locations relevant to the body specified. You can add force matrices together to specify multiple forces on multiple bodies.

To create the matrix for a specified force or torque, see externalForce.

Output Arguments

collapse all

Joint accelerations, returned as a vector. The dimension of the joint accelerations vector is equal to the degrees of freedom of the robot. Each element corresponds to a specific joint on the robot.

More About

collapse all

Dynamics Properties

When working with robot dynamics, specify the information for individual bodies of your manipulator robot using these properties of the rigidBody objects:

  • Mass — Mass of the rigid body in kilograms.

  • CenterOfMass — Center of mass position of the rigid body, specified as a vector of the form [x y z]. The vector describes the location of the center of mass of the rigid body, relative to the body frame, in meters. The centerOfMass object function uses these rigid body property values when computing the center of mass of a robot.

  • Inertia — Inertia of the rigid body, specified as a vector of the form [Ixx Iyy Izz Iyz Ixz Ixy]. The vector is relative to the body frame in kilogram square meters. The inertia tensor is a positive definite matrix of the form:

    A 3-by-3 matrix. The first row contains Ixx, Ixy, and Ixz. The second contains Ixy, Iyy, and Iyz. The third contains Ixz, Iyz, and Izz.

    The first three elements of the Inertia vector are the moment of inertia, which are the diagonal elements of the inertia tensor. The last three elements are the product of inertia, which are the off-diagonal elements of the inertia tensor.

For information related to the entire manipulator robot model, specify these rigidBodyTree object properties:

  • Gravity — Gravitational acceleration experienced by the robot, specified as an [x y z] vector in m/s2. By default, there is no gravitational acceleration.

  • DataFormat — The input and output data format for the kinematics and dynamics functions, specified as "struct", "row", or "column".

Dynamics Equations

Manipulator rigid body dynamics are governed by this equation:

ddt[qq˙]=[q˙M(q)1(C(q,q˙)q˙G(q)J(q)TfExt+τ)]

also written as:

M(q)q¨=C(q,q˙)q˙G(q)J(q)TfExt+τ

where:

  • M(q) — is a joint-space mass matrix based on the current robot configuration. Calculate this matrix by using the massMatrix object function.

  • C(q,q˙) — are the Coriolis terms, which are multiplied by q˙ to calculate the velocity product. Calculate the velocity product by using by the velocityProduct object function.

  • G(q) — is the gravity torques and forces required for all joints to maintain their positions in the specified gravity Gravity. Calculate the gravity torque by using the gravityTorque object function.

  • J(q) — is the geometric Jacobian for the specified joint configuration. Calculate the geometric Jacobian by using the geometricJacobian object function.

  • fExt — is a matrix of the external forces applied to the rigid body. Generate external forces by using the externalForce object function.

  • τ — are the joint torques and forces applied directly as a vector to each joint.

  • q,q˙,q¨ — are the joint configuration, joint velocities, and joint accelerations, respectively, as individual vectors. For revolute joints, specify values in radians, rad/s, and rad/s2, respectively. For prismatic joints, specify in meters, m/s, and m/s2.

To compute the dynamics directly, use the forwardDynamics object function. The function calculates the joint accelerations for the specified combinations of the above inputs.

To achieve a certain set of motions, use the inverseDynamics object function. The function calculates the joint torques required to achieve the specified configuration, velocities, accelerations, and external forces.

References

[1] Featherstone, Roy. Rigid Body Dynamics Algorithms. Springer US, 2008. DOI.org (Crossref), doi:10.1007/978-1-4899-7560-7.

Extended Capabilities

Version History

Introduced in R2017a

expand all