Skip to content
Draft
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
44 changes: 40 additions & 4 deletions models/iris_with_standoffs/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,10 @@
</inertia>
</inertial>
<collision name='base_collision'>
<pose>0 0 -0.08 0 0 0</pose>
<geometry>
<box>
<size>0.47 0.47 0.23</size>
</box>
<mesh>
<uri>model://iris_with_standoffs/meshes/iris.dae</uri>
</mesh>
</geometry>
<surface>
<contact>
Expand All @@ -41,6 +40,43 @@
</friction>
</surface>
</collision>
<collision name='front_left_leg_collision'>
<pose>0.123 0.22 -0.11 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.005</radius>
<length>0.17</length>
</cylinder>
</geometry>
</collision>
<collision name='front_right_leg_collision'>
<pose>0.123 -0.22 -0.11 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.005</radius>
<length>0.17</length>
</cylinder>
</geometry>
</collision>
<collision name='rear_left_leg_collision'>
<pose>-0.140 0.21 -0.11 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.005</radius>
<length>0.17</length>
</cylinder>
</geometry>
</collision>
<collision name='rear_right_leg_collision'>
<pose>-0.140 -0.21 -0.11 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.005</radius>
<length>0.17</length>
</cylinder>
</geometry>
</collision>

<visual name='base_visual'>
<geometry>
<mesh>
Expand Down
13 changes: 13 additions & 0 deletions models/tether/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0"?>
<model>
<name>tether</name>
<version>1.0.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Nuno Marques</name>
<email>n.marques21@hotmail.com</email>
</author>
<description>
This model approximates a tether cord.
</description>
</model>
Loading