-
jenniferdavid authoredUnverified4a970bf6
f550_amazing.sdf 49.32 KiB
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="f550_amazing">
<static>false</static>
<pose>0 0 0.35 0 0 0</pose>
<!-- ######################################## LOWER_PLATE # ######################################## -->
<link name="base_link">
<gravity>true</gravity>
<pose>0 0 0.0015 0 0 0</pose>
<inertial>
<pose frame=''>0.001005 0 -0.0090035 0 -0 0</pose>
<mass>0.6</mass>
<inertia>
<ixx>0.011</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.015</iyy>
<iyz>0</iyz>
<izz>0.021</izz>
</inertia>
</inertial>
<visual name="base_link_visual">
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://f550_amazing/meshes/Lower_plate_CG.STL</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
</link>
<!-- ####################################### /LOWER_PLATE # ######################################## -->
<!--
<joint name="fixed to ground" type="fixed">
<parent>world</parent>
<child>base_link</child>
</joint>
-->
<!-- ######################################## TOP_PLATE ############################################ -->
<link name="Top_plate_link">
<gravity>true</gravity>
<pose>0 0 0.0375 0 0 2.09439510239</pose>
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<visual name="visual_Top_plate">
<geometry>
<mesh>