Main Content

rigidBody

Create a rigid body

Description

TherigidBodyobject represents a rigid body. A rigid body is the building block for any tree-structured robot manipulator. EachrigidBodyhas arigidBodyJointobject attached to it that defines how the rigid body can move. Rigid bodies are assembled into a tree-structured robot model usingrigidBodyTree.

Set a joint object to theJointproperty before callingaddBodyto add the rigid body to the robot model. When a rigid body is in a rigid body tree, you cannot directly modify its properties because it corrupts the relationships between bodies. UsereplaceJointto modify the entire tree structure.

Creation

Description

example

body= rigidBody(name)creates a rigid body with the specified name. By default, the body comes with a fixed joint.

Input Arguments

expand all

Name of the rigid body, specified as a string scalar or character vector. This name must be unique to the body so that it can be accessed in arigidBodyTreeobject.

Properties

expand all

Name of the rigid body, specified as a string scalar or character vector. This name must be unique to the body so that it can be found in arigidBodyTreeobject.

Data Types:char|string

rigidBodyJointobject, specified as a handle. By default, the joint is'fixed'type.

Mass of rigid body, specified as a numeric scalar in kilograms.

Center of mass position of rigid body, specified as an[x y z]向量。向量描述了位置of the center of mass relative to the body frame in meters.

Inertia of rigid body, specified as a[Ixx Iyy Izz Iyz Ixz Ixy]vector relative to the body frame in kilogram square meters. The first three elements of the vector are the diagonal elements of theinertia tensor. The last three elements are the off-diagonal elements of the inertia tensor. The inertia tensor is a positive semi-definite symmetric matrix:

Rigid body parent, specified as arigidBodyobject handle. The rigid body joint defines how this body can move relative to the parent. This property is empty until the rigid body is added to arigidBodyTreerobot model.

Rigid body children, specified as a cell array ofrigidBodyobject handles. These rigid body children are all attached to this rigid body object. This property is empty until the rigid body is added to arigidBodyTreerobot model, and at least one other body is added to the tree with this body as its parent.

Visual geometries, specified as a cell array of string scalars or character vectors. Each character vector describes a type and source of a visual geometry. For example, if a mesh file,link_0.stl, is attached to the rigid body, the visual would beMesh:link_0.stl. Visual geometries are added to the rigid body usingaddVisual.

Collision geometries, specified as a cell array of character vectors. Each character vector describes the type of collision object and relevant parameters of the collision geometry. To modify the collision geometries for a rigid body, use theaddCollisionandclearCollisionfunctions.

Object Functions

copy Create a deep copy of rigid body
addCollision Add collision geometry to rigid body
addVisual Add visual geometry data to rigid body
clearCollision Clear all attached collision geometries
clearVisual Clear all visual geometries

Examples

collapse all

Add a rigid body and corresponding joint to a rigid body tree. Each rigidBodyobject contains arigidBodyJointobject and must be added to the rigidBodyTreeusingaddBody.

Create a rigid body tree.

rbtree = rigidBodyTree;

Create a rigid body with a unique name.

body1 = rigidBody('b1');

Create a revolute joint. By default, the rigidBodyobject comes with a fixed joint. Replace the joint by assigning a newrigidBodyJointobject to thebody1.Jointproperty.

jnt1 = rigidBodyJoint('jnt1','revolute'); body1.Joint = jnt1;

Add the rigid body to the tree. Specify the body name that you are attaching the rigid body to. Because this is the first body, use the base name of the tree.

basename = rbtree.BaseName; addBody(rbtree,body1,basename)

Useshowdetailson the tree to confirm the rigid body and joint were added properly.

showdetails(rbtree)
-------------------- Robot: (1 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 b1 jnt1 revolute base(0) --------------------

Use the Denavit-Hartenberg (DH) parameters of the Puma560® robot to build a robot. Each rigid body is added one at a time, with the child-to-parent transform specified by the joint object.

The DH parameters define the geometry of the robot with relation to how each rigid body is attached to its parent. For convenience, setup the parameters for the Puma560 robot in a matrix[1]. The Puma robot is a serial chain manipulator. The DH parameters are relative to the previous line in the matrix, corresponding to the previous joint attachment.

dhparams = [0 pi/2 0 0; 0.4318 0 0 0 0.0203 -pi/2 0.15005 0; 0 pi/2 0.4318 0; 0 -pi/2 0 0; 0 0 0 0];

Create a rigid body tree object to build the robot.

robot = rigidBodyTree;

Create the first rigid body and add it to the robot. To add a rigid body:

  1. Create arigidBodyobject and give it a unique name.

  2. Create arigidBodyJointobject and give it a unique name.

  3. UsesetFixedTransformto specify the body-to-body transformation using DH parameters. The last element of the DH parameters,theta, is ignored because the angle is dependent on the joint position.

  4. CalladdBodyto attach the first body joint to the base frame of the robot.

body1 = rigidBody('body1'); jnt1 = rigidBodyJoint('jnt1','revolute'); setFixedTransform(jnt1,dhparams(1,:),'dh'); body1.Joint = jnt1; addBody(robot,body1,'base')

Create and add other rigid bodies to the robot. Specify the previous body name when callingaddBodyto attach it. Each fixed transform is relative to the previous joint coordinate frame.

body2 = rigidBody('body2'); jnt2 = rigidBodyJoint('jnt2','revolute'); body3 = rigidBody('body3'); jnt3 = rigidBodyJoint('jnt3','revolute'); body4 = rigidBody('body4'); jnt4 = rigidBodyJoint('jnt4','revolute'); body5 = rigidBody(“body5”); jnt5 = rigidBodyJoint('jnt5','revolute'); body6 = rigidBody('body6'); jnt6 = rigidBodyJoint('jnt6','revolute'); setFixedTransform(jnt2,dhparams(2,:),'dh'); setFixedTransform(jnt3,dhparams(3,:),'dh'); setFixedTransform(jnt4,dhparams(4,:),'dh'); setFixedTransform(jnt5,dhparams(5,:),'dh'); setFixedTransform(jnt6,dhparams(6,:),'dh'); body2.Joint = jnt2; body3.Joint = jnt3; body4.Joint = jnt4; body5.Joint = jnt5; body6.Joint = jnt6; addBody(robot,body2,'body1') addBody(robot,body3,'body2') addBody(robot,body4,'body3') addBody(robot,body5,'body4') addBody(robot,body6,“body5”)

确认你的机器人建于妥善利用theshowdetailsorshowfunction.showdetailslists all the bodies in the MATLAB® command window.showdisplays the robot with a given configuration (home by default). Calls toaxismodify the axis limits and hide the axis labels.

showdetails(robot)
-------------------- 机器人:身体(6)Idx身体Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 body1 jnt1 revolute base(0) body2(2) 2 body2 jnt2 revolute body1(1) body3(3) 3 body3 jnt3 revolute body2(2) body4(4) 4 body4 jnt4 revolute body3(3) body5(5) 5 body5 jnt5 revolute body4(4) body6(6) 6 body6 jnt6 revolute body5(5) --------------------
show(robot); axis([-0.5,0.5,-0.5,0.5,-0.5,0.5]) axisoff

References

[1] Corke, P. I., and B. Armstrong-Helouvry. “A Search for Consensus among Model Parameters Reported for the PUMA 560 Robot.”Proceedings of the 1994 IEEE International Conference on Robotics and Automation, IEEE Comput. Soc. Press, 1994, pp. 1608–13.DOI.org (Crossref), doi:10.1109/ROBOT.1994.351360.

References

[1] Craig, John J.Introduction to Robotics: Mechanics and Control. Reading, MA: Addison-Wesley, 1989.

[2] Siciliano, Bruno. Robotics: Modelling, Planning and Control. London: Springer, 2009.

Extended Capabilities

C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.

Version History

Introduced in R2016b

expand all

Behavior change in future release