velocityProduct
Joint torques that cancel velocity-induced forces
Description
computes the joint torques required to cancel the forces induced by
the specified joint velocities under a certain joint configuration.
Gravity torque is not included in this calculation.jointTorq
= velocityProduct(robot
,configuration
,jointVel
)
Examples
Compute Velocity-Induced Joint Torques
Load a model of the Quanser Q-Arm from the Robotics System Toolbox™ loadrobot
, which is returned as a rigidBodyTree
object. Update the data format to "row"
. For all dynamics calculations, the data format must be either "row"
or "column"
.
robot = loadrobot("quanserQArm", DataFormat="row", Gravity=[0 0 -9.81]); show(robot);
Set the joint velocity vector.
qdot = [0.2 -0.3 0 0.1];
Compute the joint torques required to cancel the velocity-induced joint torques at the robot home configuration ([]
input). The velocity-induced joint torques equal the negative of the velocityProduct
output.
tau = -velocityProduct(robot,[],qdot)
tau = 1×4
0.0045 0.0015 -0.0023 -0.0000
Input Arguments
robot
— Robot model
rigidBodyTree
object
Robot model, specified as a rigidBodyTree
object. To use the
velocityProduct
function, set
the DataFormat
property to
either 'row'
or
'column'
.
configuration
— Robot configuration
vector
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'
.
jointVel
— Joint velocities
vector
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'
.
Output Arguments
jointTorq
— Joint torques
vector
Joint torques, specified as a vector. Each element corresponds to a torque applied to a specific joint.
More About
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. ThecenterOfMass
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: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:
also written as:
where:
— is a joint-space mass matrix based on the current robot configuration. Calculate this matrix by using the
massMatrix
object function.— are the Coriolis terms, which are multiplied by to calculate the velocity product. Calculate the velocity product by using by the
velocityProduct
object function.— 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 thegravityTorque
object function.— is the geometric Jacobian for the specified joint configuration. Calculate the geometric Jacobian by using the
geometricJacobian
object function.— 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.
— 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.
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Usage notes and limitations:
When creating the rigidBodyTree
object, use the syntax that specifies the
MaxNumBodies
as an upper bound for adding bodies to the robot model.
You must also specify the DataFormat
property as a name-value pair. For
example:
robot = rigidBodyTree("MaxNumBodies",15,"DataFormat","row")
To minimize data usage, limit the upper bound to a number close to the expected number of bodies in the model. All data formats are supported for code generation. To use the dynamics functions, the data format must be set to "row"
or "column"
.
The show
and showdetails
functions do not support code generation.
Version History
Introduced in R2017aR2024a: Static memory allocation support
velocityProduct
now supports code generation with disabled dynamic memory allocation. For more information about disabling dynamic memory allocation, see Set Dynamic Memory Allocation Threshold (MATLAB Coder).
See Also
rigidBodyTree
| inverseDynamics
| gravityTorque
| massMatrix
Commande MATLAB
Vous avez cliqué sur un lien qui correspond à cette commande MATLAB :
Pour exécuter la commande, saisissez-la dans la fenêtre de commande de MATLAB. Les navigateurs web ne supportent pas les commandes MATLAB.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list:
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)