-
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>
</collision>
<!-- Appearence box -->
<visual name='visual'>
<geometry>
<box>
<size>2.375 2.495 3.353</size>
</box>
</geometry>
</visual>
</link>
<!-- trailer -->
<link name='trailer'>
<!-- pose of the vehicle wrt model origin -->
<pose>-5.25 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>6. 2.495 0.2</size>
</box>
</geometry>
</collision>
<!-- Appearence box -->
<visual name='visual'>
<geometry>
<box>
<size>6. 2.495 0.2</size>
</box>
</geometry>
</visual>
</link>
<!-- Front left wheel -->
<link name="front_left_wheel">
<pose>1 1.2475 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- Front right wheel -->
<link name="front_right_wheel">
<pose>1 -1.2475 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- Rear left wheel -->
<link name="rear_left_wheel">
<pose>-2 1.2475 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- Rear right wheel -->
<link name="rear_right_wheel">
<pose>-2 -1.2475 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- trailer left wheel -->
<link name="trailer_left_wheel">
<pose>-5.5 1.2 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- Trailer right wheel -->
<link name="trailer_right_wheel">
<pose>-5.5 -1.2 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- trailer left wheel 2 -->
<link name="trailer_left_wheel_2">
<pose>-7.3 1.2 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- trailer right wheel 2 -->
<link name="trailer_right_wheel_2">
<pose>-7.3 -1.2 0.882 0 1.5707 1.5707</pose>
<inertial> <!-- Inertia of a cylinder: http://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<mass>100.0</mass>
<inertia>
<ixx>6.5</ixx> <!-- for a cylinder: ixx = 0.083 * mass * (3*radius^2 + height) -->
<ixy>0.0</ixy> <!-- for a cylinder: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a cylinder: ixz = 0 -->
<iyy>6.5</iyy> <!-- for a cylinder: iyy = 0.083 * mass * (3*radius^2 + height) -->
<iyz>0.0</iyz> <!-- for a cylinder: iyz = 0 -->
<izz>12.25</izz> <!-- for a cylinder: izz = 0.5 * mass * radius^2 -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.882</radius>
<length>0.3</length>
</cylinder>
</geometry>
</visual>
</link>
<joint name="trailer_left_wheel_hinge" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>trailer_left_wheel</child>
<parent>trailer</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="trailer_right_wheel_hinge" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>trailer_right_wheel</child>
<parent>trailer</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="trailer_left_wheel_hinge_2" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>trailer_left_wheel</child>
<parent>trailer</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="trailer_right_wheel_hinge_2" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>trailer_right_wheel</child>
<parent>trailer</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="front_left_wheel_hinge" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>front_left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="front_right_wheel_hinge" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>front_right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="rear_left_wheel_hinge" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>rear_left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="rear_right_wheel_hinge" type="revolute">
<pose>0 0 0 0 0 0</pose>
<child>rear_right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="main_cabinet_hinge" type="revolute">
<pose>1.5 0 3 0 0 0</pose>
<child>cabinet</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<joint name="trailer_cabinet_hinge" type="revolute">
<pose>-5.75 0 1 0 0 0</pose>
<child>trailer</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<include>
<uri>model://hokuyo</uri>
<name>front_lidar</name>
<pose>2.75 0 1 0 0 0</pose> <!-- pose in global coordinate frame -->
</include>
<include>
<uri>model://hokuyo</uri>
<name>rear_lidar</name>
<pose>-8.3 0 1 0 0 3</pose> <!-- pose in global coordinate frame -->
</include>
<include>
<uri>model://camera</uri>
<name>front_camera</name>
<pose>2.75 0 4 0 0 0</pose> <!-- pose in global coordinate frame -->
</include>
<joint name="front_lidar_joint" type="revolute">
<child>front_lidar::link</child>
<parent>chassis</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<joint name="rear_lidar_joint" type="revolute">
<child>rear_lidar::link</child>
<parent>trailer</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<joint name="front_camera" type="revolute">
<child>front_camera::link</child>
<parent>cabinet</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
</model>
</sdf>