gravityTorque
Joint torques that compensate gravity
Description
Examples
Load a Techman™ TM12 from the Robotics System Toolbox™ loadrobot. The robot is specified as a rigidBodyTree object.
robot = loadrobot("tm12");Set the data format to "row". For all dynamics calculations, the data format must be either "row" or "column". Update the Gravity property.
robot.DataFormat = "row";
robot.Gravity = [0 0 -9.81];Get a random configuration for the robot.
q = randomConfiguration(robot);
Compute the gravity-compensating torques for each joint.
gtau = gravityTorque(robot,q)
gtau = 1×6
0.0000 60.4466 16.4834 -2.2469 0.6922 0
Input Arguments
Robot model, specified as a rigidBodyTree object. To use the
gravityTorque 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'.
Output Arguments
Gravity-compensating torque for each joint, returned as a vector.
More About
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. ThecenterOfMassobject 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
Inertiavector 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".
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
massMatrixobject function.— are the Coriolis terms, which are multiplied by to calculate the velocity product. Calculate the velocity product by using by the
velocityProductobject 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 thegravityTorqueobject function.— is the geometric Jacobian for the specified joint configuration. Calculate the geometric Jacobian by using the
geometricJacobianobject function.— is a matrix of the external forces applied to the rigid body. Generate external forces by using the
externalForceobject 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.
References
[1] Featherstone, Roy. Rigid Body Dynamics Algorithms. Springer US, 2008. DOI.org (Crossref), doi:10.1007/978-1-4899-7560-7.
Extended Capabilities
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 R2017agravityTorque 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
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
选择网站
选择网站以获取翻译的可用内容,以及查看当地活动和优惠。根据您的位置,我们建议您选择:。
您也可以从以下列表中选择网站:
如何获得最佳网站性能
选择中国网站(中文或英文)以获得最佳网站性能。其他 MathWorks 国家/地区网站并未针对您所在位置的访问进行优化。
美洲
- América Latina (Español)
- Canada (English)
- United States (English)
欧洲
- 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)