writefile
Description
writefile(
generates a unified robot
description format (URDF) file for the rigid body tree robot model specified in the exporter
)urdfExporter
object exporter
.
writefile(___,
specifies additional options using one or more name-value pair arguments in addition to the
input argument in the previous syntax.Name=Value
)
Examples
Export Robot Model Details in URDF File Format
This example shows how to load a robot as a rigidBodyTree
model and export the robot details as a URDF file.
Load a rigidBodyTree
robot model. The rigidBodyTree
object contains kinematic and dynamic constraints and visual meshes for the specified robot geometry.
robotRBT = loadrobot("abbIrb120");
Create a rigidBody
object with a unique name.
body1 = rigidBody("link1");
By default, the rigidBody
object comes with a fixed joint. Replace the joint by assigning a new rigidBodyJoint
object to the body1.Joint
property.
body1.Joint = rigidBodyJoint(jnt1="revolute");
Add the rigidBody
object to the rigidBodyTree
robot model. Specify the body name to which you are attaching the rigid body. Use the base name of the tree for the first body.
basename = robotRBT.BaseName; addBody(robotRBT,body1,basename);
Confirm that the rigid body and joint are correct by using showdetails
.
showdetails(robotRBT)
-------------------- Robot: (9 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) 9 link1 jnt1 revolute base_link(0) --------------------
Visualize the robot model.
show(robotRBT)
ans = Axes (Primary) with properties: XLim: [-1 1] YLim: [-1 1] XScale: 'linear' YScale: 'linear' GridLineStyle: '-' Position: [0.1300 0.1100 0.7750 0.8150] Units: 'normalized' Show all properties
Add visuals to the robot model.
body9 = robotRBT.Bodies{9}; addVisual(body9,box=[0.1 0.1 0.1]);
Visualize the robot model with the added visuals.
show(robotRBT)
ans = Axes (Primary) with properties: XLim: [-1 1] YLim: [-1 1] XScale: 'linear' YScale: 'linear' GridLineStyle: '-' Position: [0.1300 0.1100 0.7750 0.8150] Units: 'normalized' Show all properties
Create a URDF exporter object. Package the mesh and URDF details in one folder.
exporter = urdfExporter(robotRBT); exporter.ExportMesh = true;
Write the packaged mesh and URDF details into the specified file.
writefile(exporter,OutputfileName="abbIrb120.urdf")
Input Arguments
exporter
— URDF exporter
urdfExporter
object
URDF exporter specified as a urdfExporter
object.
Name-Value Arguments
Specify optional pairs of arguments as
Name1=Value1,...,NameN=ValueN
, where Name
is
the argument name and Value
is the corresponding value.
Name-value arguments must appear after other arguments, but the order of the
pairs does not matter.
Example: writefile(exporter,
OutputfileName="abbIrb120.urdf")
OutputFileName
— Name of generated URDF file
input variable name (default) | string scalar | character vector
Name of the generated URDF file, specified as a string scalar or character vector. You can also specify this input as a pathname corresponding to the location at which you want to generate the URDF file.
Example: "abbIrb120.urdf"
,
"C:/URDF/abbIrb120.urdf"
Data Types: char
| string
RobotName
— Robot name attribute
"Robot"
(default) | string scalar | character vector
Robot name attribute corresponding to the robot name
tag in the
generated URDF file, specified as a string scalar or character vector. The function
returns as a valid robot model name such as "abbIrb120"
,
"abbIrb120T"
, "abbIrb1600"
.
Example: "abbIrb120"
Data Types: char
| string
ExportMesh
— Option to enable mesh file export
false
or 0
(default) | true
or 1
Option to enable mesh file export, specified as a numeric or logical value of
0 (false)
or 1 (true)
. The generated ZIP
package contains the output URDF files and mesh files.
Data Types: logical
| numeric
AbsoluteTolerance
— Maximum permissible difference in exported values
sqrt(eps)
(default) | positive scalar
Maximum permissible difference in the values under tags in exported URDF,
specified as a positive scalar. The default value is sqrt(eps)
,
where eps
returns the distance from 1.0
to the
next largest double-precision number, which is equal to
2-52
. For more information, see
eps
.
Data Types: single
| double
Version History
Introduced in R2023b
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 (한국어)