Main Content

externalForce

Compose external force matrix relative to base

Description

fext = externalForce(robot,bodyname,wrench) composes the external force matrix, which you can use as inputs to inverseDynamics and forwardDynamics to apply an external force, wrench, to the body specified by bodyname. The wrench input is assumed to be in the base frame.

example

fext = externalForce(robot,framename,wrench) composes the external force matrix, which you can use as inputs to inverseDynamics and forwardDynamics to apply an external force, wrench, to the frame specified by framename. The wrench input is assumed to be in the base frame.

fext = externalForce(robot,bodyname,wrench,configuration) composes the external force matrix assuming that wrench is in the bodyname frame for the specified configuration. The force matrix fext is given in the base frame.

example

fext = externalForce(robot,framename,wrench,configuration) composes the external force matrix assuming that wrench is in the framename frame for the specified configuration. The force matrix fext is given in the base frame.

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

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 externalForce function, set the DataFormat property to either "row" or "column".

Name of body to which the external force is applied, specified as a string scalar or character vector. This body name must match a body on the robot object.

Data Types: char | string

Name of frame to which the external force is applied, specified as a string scalar or character vector. This frame name must match a frame on the robot object.

Data Types: char | string

Torques and forces applied to the body, specified as a [Tx Ty Tz Fx Fy Fz] vector. The first three elements of the wrench correspond to the moments around xyz-axes. The last three elements are linear forces along the same axes. Unless you specify the robot configuration, the wrench is assumed to be relative to the base frame.

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

Output Arguments

collapse all

External force matrix, returned as either an n-by-6 or 6-by-n matrix, where n is the velocity number (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 composed 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. Use the external force matrix to specify external forces to dynamics functions inverseDynamics and forwardDynamics.

More About

collapse all

References

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

Extended Capabilities

expand all

Version History

Introduced in R2017a

expand all