-
jenniferdavid authoredf0948038
model.sdf 20.42 KiB
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="at_volvo">
<static>false</static>
<!-- Main vehicle Body -->
<link name='chassis'>
<!-- pose of the vehicle wrt model origin -->
<pose>0 0 1 0 0 0</pose>
<!-- Inertia of a box: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<inertial>
<mass>2300.0</mass>
<inertia>
<ixx>937.5</ixx> <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
<ixy>0.0</ixy> <!-- for a box: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a box: ixz = 0 -->
<iyy>8520.8</iyy> <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
<iyz>0.0</iyz> <!-- for a box: iyz = 0 -->
<izz>9083.3</izz> <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
</inertia>
</inertial>
<!-- Collision box -->
<collision name='collision'>
<geometry>
<box>
<size>5.250 2.495 0.4</size>
</box>
</geometry>
</collision>
<!-- Appearence box -->
<visual name='visual'>
<geometry>
<box>
<size>5.250 2.495 0.4</size>
</box>
</geometry>
</visual>
</link>
<!-- Main cabinet -->
<link name='cabinet'>
<!-- pose of the vehicle wrt model origin -->
<pose>1.5 0 2.75 0 0 0</pose>
<!-- Inertia of a box: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<inertial>
<mass>1000.0</mass>
<inertia>
<ixx>937.5</ixx> <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
<ixy>0.0</ixy> <!-- for a box: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a box: ixz = 0 -->
<iyy>8520.8</iyy> <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
<iyz>0.0</iyz> <!-- for a box: iyz = 0 -->
<izz>9083.3</izz> <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
</inertia>
</inertial>
<!-- Collision box -->
<collision name='collision'>
<geometry>
<box>
<size>2.375 2.495 3.353</size>
</box>
</geometry>