Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add documentation for SDFormat/Gazebo extension to URDF #88

Merged
merged 5 commits into from
Mar 23, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions manifest.xml
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,20 @@
<skill>intermediate</skill>
</tutorial>

<tutorial title="SDFormat extensions to URDF (the 'gazebo' tag)" ref='sdformat_urdf_extensions' type='tutorial'>
<markdown version="1.6">urdf/sdf_extensions.md</markdown>
<description>
Describes how the "gazebo" tag can be used to extend URDF to include SDFormat content.

</description>
<tags>
<tag>model</tag>
<tag>urdf</tag>
<tag>gazebo</tag>
</tags>
<skill>intermediate</skill>
</tutorial>

<tutorial title="Proposal Procedure and Format" ref='proposal_format' type='documentation'>
<markdown version="1.7">developers/proposal_format.md</markdown>
<description>
Expand Down Expand Up @@ -297,6 +311,7 @@
<tutorial>pose_frame_semantics</tutorial>
<tutorial>composition</tutorial>
<tutorial>param_passing_tutorial</tutorial>
<tutorial>sdformat_urdf_extensions</tutorial>
</tutorials>
</category>

Expand Down
37 changes: 37 additions & 0 deletions urdf/examples/disable_fixed_joint_lumping_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='disable_fixed_joint_lumping_example'>
<link name='base_link'>
<inertial>
<mass value='0.25' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="2"/>
</geometry>
</collision>
</link>
<joint name='j1' type='fixed'>
<parent link='base_link'/>
<child link='end_effector'/>
<origin xyz='0 0 1' rpy='0 0 0'/>
</joint>
<link name='end_effector'>
<inertial>
<mass value='0.25' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<visual>
<origin xyz="2 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="2"/>
</geometry>
</visual>
</link>
<gazebo reference='j1'>
<disableFixedJointLumping>true</disableFixedJointLumping>
</gazebo>
</robot>

34 changes: 34 additions & 0 deletions urdf/examples/fixed_joint_lumping_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='fixed_joint_lumping_example'>
<link name='base_link'>
<inertial>
<mass value='0.25' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="2"/>
</geometry>
</collision>
</link>
<joint name='j1' type='fixed'>
<parent link='base_link'/>
<child link='end_effector'/>
<origin xyz='0 0 1' rpy='0 0 0'/>
</joint>
<link name='end_effector'>
<inertial>
<mass value='0.25' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<visual>
<origin xyz="2 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="2"/>
</geometry>
</visual>
</link>
</robot>

24 changes: 24 additions & 0 deletions urdf/examples/friction_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='friction_example'>
<link name='base_link'>
<inertial>
<mass value='0.12' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<collision>
<geometry>
<sphere radius="2"/>
</geometry>
</collision>
<collision>
<geometry>
<cylinder radius="1" length="2"/>
</geometry>
</collision>
</link>
<gazebo reference='base_link'>
<mu1>0.25</mu1>
</gazebo>
</robot>

26 changes: 26 additions & 0 deletions urdf/examples/joint_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='joint_example'>
<link name='base_link'>
<inertial>
<mass value='0.12' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
</link>
<joint name='j1' type='continuous'>
<parent link='base_link'/>
<child link='end_effector'/>
<origin xyz='0 0 1' rpy='0 0 0'/>
</joint>
<link name='end_effector'>
<inertial>
<mass value='0.12' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
</link>
<gazebo reference='j1'>
<springReference>0.5</springReference>
<springStiffness>0.25</springStiffness>
</gazebo>
</robot>

27 changes: 27 additions & 0 deletions urdf/examples/link_ref_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='link_ref_example'>
<link name='base_link'>
<inertial>
<mass value='0.1' />
<origin rpy='0 0 0' xyz='0 0 0' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="2"/>
</geometry>
</collision>
</link>
<gazebo reference='base_link'>
<mu1>0.5</mu1> <!-- Will create collision/surface/friction/ode/mu -->

<!-- <light> is inserted directly into the link since it is not a special element -->
<light name="point_light" type="point">
<diffuse>1.0 1.0 1.0 1.0</diffuse>
<specular>0.1 0.1 0.1 1.0</specular>
</light>
</gazebo>
</robot>

19 changes: 19 additions & 0 deletions urdf/examples/material_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='material_example'>
<link name='base_link'>
<inertial>
<mass value='0.1' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<visual>
<geometry>
<sphere radius="2"/>
</geometry>
</visual>
</link>
<gazebo reference='base_link'>
<material>Gazebo/Orange</material>
</gazebo>
</robot>

23 changes: 23 additions & 0 deletions urdf/examples/material_visual_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='material_example'>
<link name='base_link'>
<inertial>
<mass value='0.12' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<visual>
<geometry>
<sphere radius="2"/>
</geometry>
</visual>
</link>
<gazebo reference='base_link'>
<visual>
<material>
<diffuse>0 0 1 1 </diffuse>
</material>
</visual>
</gazebo>
</robot>

10 changes: 10 additions & 0 deletions urdf/examples/no_ref_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='no_ref_example'>
<link name='world'/>
<gazebo>
<static>true</static>
<plugin name='testPlugin' filename='testFileName'/>
</gazebo>
</robot>

37 changes: 37 additions & 0 deletions urdf/examples/preserve_fixed_joint_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='preserve_fixed_joint_lumping_example'>
<link name='base_link'>
<inertial>
<mass value='0.25' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="2"/>
</geometry>
</collision>
</link>
<joint name='j1' type='fixed'>
<parent link='base_link'/>
<child link='end_effector'/>
<origin xyz='0 0 1' rpy='0 0 0'/>
</joint>
<link name='end_effector'>
<inertial>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

<inertia /> block is missing, which deviates from prior example

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good catch. Changed in 8d1ad17. The resulting SDFormat now also has the end_effector_visual. Not sure why it was missing before.

<mass value='0.25' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<visual>
<origin xyz="2 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="2"/>
</geometry>
</visual>
</link>
<gazebo reference='j1'>
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>
</robot>

27 changes: 27 additions & 0 deletions urdf/examples/visual_example.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version='1.0' encoding='UTF-8'?>
<!--URDF-->
<robot name='visual_example'>
<link name='base_link'>
<inertial>
<mass value='0.12' />
<inertia ixx='0.01' ixy='0' ixz='0' iyy='0.01' iyz='0' izz='0.01' />
</inertial>
<visual>
<geometry>
<sphere radius="2"/>
</geometry>
</visual>
<visual>
<origin xyz="2 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="1" radius="2"/>
</geometry>
</visual>
</link>
<gazebo reference='base_link'>
<visual>
<transparency>0.25</transparency>
</visual>
</gazebo>
</robot>

Loading