Main Content

rigidBody

Create a rigid body

Description

The rigidBody object represents a rigid body. A rigid body is the building block for any tree-structured robot manipulator. Each rigidBody has a rigidBodyJoint object attached to it that defines how the rigid body can move. Rigid bodies are assembled into a tree-structured robot model using rigidBodyTree.

Set a joint object to the Joint property before calling addBody to 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. Use replaceJoint to modify the entire tree structure.

Creation

Description

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

example

body = rigidBody(name,"MaxNumCollisions",N) specifies an upper bound on the number of collision geometries that you can add to the rigid body in generated code.

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 a rigidBodyTree object.

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 a rigidBodyTree object.

Data Types: char | string

rigidBodyJoint object, 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] vector. The vector describes the location 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 the inertia 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 a rigidBody object 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 a rigidBodyTree robot model.

Rigid body children, specified as a cell array of rigidBody object handles. These rigid body children are all attached to this rigid body object. This property is empty until the rigid body is added to a rigidBodyTree robot 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 be Mesh:link_0.stl. Visual geometries are added to the rigid body using addVisual.

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 the addCollision and clearCollision functions.

Object Functions

copyCreate selective deep copy of rigid body
addCollisionAdd collision geometry to rigid body
addVisualAdd visual geometry data to rigid body
clearCollisionClear all attached collision geometries
clearVisualClear all visual geometries
getVisualGet visual geometries of the rigid body

Examples

collapse all

Add a rigid body and corresponding joint to a rigid body tree. Each rigidBody object contains a rigidBodyJoint object and must be added to the rigidBodyTree using addBody.

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 rigidBody object comes with a fixed joint. Replace the joint by assigning a new rigidBodyJoint object to the body1.Joint property.

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)

Use showdetails on 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 row 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 a rigidBody object and give it a unique name.

  2. Create a rigidBodyJoint object and give it a unique name.

  3. Use setFixedTransform to 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. Call addBody to 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 calling addBody to 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')

Verify that your robot was built properly by using the showdetails or show function. showdetails lists all the bodies in the MATLAB® command window. show displays the robot with a given configuration (home by default). Calls to axis modify the axis limits and hide the axis labels.

showdetails(robot)
--------------------
Robot: (6 bodies)

 Idx    Body 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])
axis off

Figure contains an axes object. The hidden axes object with xlabel X, ylabel Y contains 13 objects of type patch, line. These objects represent base, body1, body2, body3, body4, body5, body6.

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

Version History

Introduced in R2016b

expand all