addBody
Add body to robot
Description
addBody(
adds a rigid body to the robot object and is attached to the rigid body parent
specified by robot
,body
,parentname
)parentname
. The
body
property defines how
this body moves relative to the parent body.
Examples
Attach Rigid Body and Joint to Rigid Body Tree
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) --------------------
Build Manipulator Robot Using Denavit-Hartenberg Parameters
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:
Create a
rigidBody
object and give it a unique name.Create a
rigidBodyJoint
object and give it a unique name.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.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
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.
Modify a Robot Rigid Body Tree Model
Make changes to an existing rigidBodyTree
object. You can get replace joints, bodies and subtrees in the rigid body tree.
Load an ABB IRB-120T manipulator from the Robotics System Toolbox™ loadrobot
. It is specified as a rigidBodyTree
object.
manipulator = loadrobot("abbIrb120T");
View the robot with show
and read the details of the robot using showdetails
.
show(manipulator);
showdetails(manipulator)
-------------------- Robot: (8 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 base base_link-base fixed base_link(0) 2 link_1 joint_1 revolute base_link(0) link_2(3) 3 link_2 joint_2 revolute link_1(2) link_3(4) 4 link_3 joint_3 revolute link_2(3) link_4(5) 5 link_4 joint_4 revolute link_3(4) link_5(6) 6 link_5 joint_5 revolute link_4(5) link_6(7) 7 link_6 joint_6 revolute link_5(6) tool0(8) 8 tool0 joint6-tool0 fixed link_6(7) --------------------
Get a specific body to inspect the properties. The only child of the link_3
body is the link_4
body. You can copy a specific body as well.
body3 = getBody(manipulator,"link_3");
childBody = body3.Children{1}
childBody = rigidBody with properties: Name: 'link_4' Joint: [1x1 rigidBodyJoint] Mass: 1.3280 CenterOfMass: [0.2247 1.5000e-04 4.1000e-04] Inertia: [0.0028 0.0711 0.0723 1.3052e-05 -1.3878e-04 -6.6037e-05] Parent: [1x1 rigidBody] Children: {[1x1 rigidBody]} Visuals: {'Mesh Filename link_4.stl'} Collisions: {'Mesh Filename link_4.stl'}
body3Copy = copy(body3);
Replace the joint on the link_3
body. You must create a new Joint
object and use replaceJoint
to ensure the downstream body geometry is unaffected. Call setFixedTransform
if necessary to define a transform between the bodies instead of with the default identity matrices.
newJoint = rigidBodyJoint("prismatic"); replaceJoint(manipulator,"link_3",newJoint); showdetails(manipulator)
-------------------- Robot: (8 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 base base_link-base fixed base_link(0) 2 link_1 joint_1 revolute base_link(0) link_2(3) 3 link_2 joint_2 revolute link_1(2) link_3(4) 4 link_3 prismatic fixed link_2(3) link_4(5) 5 link_4 joint_4 revolute link_3(4) link_5(6) 6 link_5 joint_5 revolute link_4(5) link_6(7) 7 link_6 joint_6 revolute link_5(6) tool0(8) 8 tool0 joint6-tool0 fixed link_6(7) --------------------
Remove an entire body and get the resulting subtree using removeBody
. The removed body is included in the subtree.
subtree = removeBody(manipulator,"link_4")
subtree = rigidBodyTree with properties: NumBodies: 4 Bodies: {[1x1 rigidBody] [1x1 rigidBody] [1x1 rigidBody] [1x1 rigidBody]} Base: [1x1 rigidBody] BodyNames: {'link_4' 'link_5' 'link_6' 'tool0'} BaseName: 'link_3' Gravity: [0 0 0] DataFormat: 'struct'
show(subtree);
Remove the modified link_3
body. Add the original copied link_3
body to the link_2
body, followed by the returned subtree. The robot model remains the same. See a detailed comparison through showdetails
.
removeBody(manipulator,"link_3"); addBody(manipulator,body3Copy,"link_2") addSubtree(manipulator,"link_3",subtree) showdetails(manipulator)
-------------------- Robot: (8 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 base base_link-base fixed base_link(0) 2 link_1 joint_1 revolute base_link(0) link_2(3) 3 link_2 joint_2 revolute link_1(2) link_3(4) 4 link_3 joint_3 revolute link_2(3) link_4(5) 5 link_4 joint_4 revolute link_3(4) link_5(6) 6 link_5 joint_5 revolute link_4(5) link_6(7) 7 link_6 joint_6 revolute link_5(6) tool0(8) 8 tool0 joint6-tool0 fixed link_6(7) --------------------
Input Arguments
robot
— Robot model
rigidBodyTree
object
Robot model, specified as a rigidBodyTree
object.
body
— Rigid body
rigidBody
object
Rigid body, specified as a rigidBody
object.
parentname
— Parent body name
string scalar | character vector
Parent body name, specified as a string scalar or character vector. This parent body must already exist in the robot model. The new body is attached to this parent body.
Data Types: char
| string
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 R2016b
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.
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)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)