Main Content

inverseDynamics

Required joint torques for given motion

Description

jointTorq = inverseDynamics(robot) computes joint torques required for the robot to statically hold its home configuration with no external forces applied.

jointTorq = inverseDynamics(robot,configuration) computes joint torques to hold the specified robot configuration.

example

jointTorq = inverseDynamics(robot,configuration,jointVel) computes joint torques for the specified joint configuration and velocities with zero acceleration and no external forces.

jointTorq = inverseDynamics(robot,configuration,jointVel,jointAccel) computes joint torques for the specified joint configuration, velocities, and accelerations with no external forces. To specify the home configuration, zero joint velocities, or zero accelerations, use [] for that input argument.

jointTorq = inverseDynamics(robot,configuration,jointVel,jointAccel,fext) computes joint torques for the specified joint configuration, velocities, accelerations, and external forces. Use the externalForce function to generate fext.

Examples

collapse all

Use the inverseDynamics function to calculate the required joint torques to statically hold a specific robot configuration. You can also specify the joint velocities, joint accelerations, and external forces using other syntaxes.

Load an Omron eCobra-600 from the Robotics System Toolbox™ loadrobot, specified as a rigidBodyTree object. Set the gravity property and ensure the data format is set to "row". For all dynamics calculations, the data format must be either "row" or "column".

robot = loadrobot("omronEcobra600", DataFormat="row", Gravity=[0 0 -9.81]);

Generate a random configuration for robot.

q = randomConfiguration(robot);

Compute the required joint torques for robot to statically hold that configuration.

tau = inverseDynamics(robot,q)
tau = 1×4

    0.0000    0.0000  -19.6200         0

Use the externalForce function to generate force matrices to apply to a rigid body tree model. The force matrix is an m-by-6 vector that has a row for each joint on the robot to apply a six-element wrench. Use the externalForce function and specify the end effector to properly assign the wrench to the correct row of the matrix. You can add multiple force matrices together to apply multiple forces to one robot.

To calculate the joint torques that counter these external forces, use the inverseDynamics function.

Load a Universal Robots UR5e from the Robotics System Toolbox™ loadrobot, specified as a rigidBodyTree object. Update the gravity and set the data format to "row". For all dynamics calculations, the data format must be either "row" or "column"

manipulator = loadrobot("universalUR5e", DataFormat="row", Gravity=[0 0 -9.81]);
showdetails(manipulator)
--------------------
Robot: (10 bodies)

 Idx                Body Name                         Joint Name                         Joint Type                Parent Name(Idx)   Children Name(s)
 ---                ---------                         ----------                         ----------                ----------------   ----------------
   1                     base         base_link-base_fixed_joint                              fixed                    base_link(0)   
   2        base_link_inertia        base_link-base_link_inertia                              fixed                    base_link(0)   shoulder_link(3)  
   3            shoulder_link                 shoulder_pan_joint                           revolute            base_link_inertia(2)   upper_arm_link(4)  
   4           upper_arm_link                shoulder_lift_joint                           revolute                shoulder_link(3)   forearm_link(5)  
   5             forearm_link                        elbow_joint                           revolute               upper_arm_link(4)   wrist_1_link(6)  
   6             wrist_1_link                      wrist_1_joint                           revolute                 forearm_link(5)   wrist_2_link(7)  
   7             wrist_2_link                      wrist_2_joint                           revolute                 wrist_1_link(6)   wrist_3_link(8)  
   8             wrist_3_link                      wrist_3_joint                           revolute                 wrist_2_link(7)   flange(9)  
   9                   flange                     wrist_3-flange                              fixed                 wrist_3_link(8)   tool0(10)  
  10                    tool0                       flange-tool0                              fixed                       flange(9)   
--------------------

Get the home configuration for manipulator.

q = homeConfiguration(manipulator);

Set external force on shoulder_link. The input wrench vector is expressed in the base frame.

fext1 = externalForce(manipulator,"shoulder_link",[0 0 0.0 0.1 0 0]);

Set external force on the end effector, tool0. The input wrench vector is expressed in the tool0 frame.

fext2 = externalForce(manipulator,"tool0",[0 0 0.0 0.1 0 0],q);

Compute the joint torques required to balance the external forces. To combine the forces, add the force matrices together. Joint velocities and accelerations are assumed to be zero (input as []).

tau = inverseDynamics(manipulator,q,[],[],fext1+fext2)
tau = 1×6

   -0.0233  -52.4189  -14.4896   -0.0100    0.0100   -0.0000

Input Arguments

collapse all

Robot model, specified as a rigidBodyTree object. To use the inverseDynamics 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 velocity 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 accelerations, returned as a vector. The dimension of the joint accelerations vector is equal to the velocity degrees of freedom of the robot. Each element corresponds to a specific joint on the robot. To use the vector form of jointAccel, 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 velocity degrees of freedom 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 torques, returned as a vector. Each element corresponds to a torque applied to a specific joint.

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