gazebo_models/polaris_ranger_ev/model-1_3.sdf
2013-01-18 10:40:12 -08:00

263 lines
6.9 KiB
XML

<?xml version="1.0"?>
<sdf version="1.3">
<model name="Polaris Ranger EV">
<link name="chassis">
<inertial>
<mass>500.0</mass>
</inertial>
<visual name="visual">
<!-- rotate mesh to get to X-forward -->
<pose>0 0 0 0 0 -1.5708</pose>
<geometry>
<mesh>
<uri>model://polaris_ranger_ev/meshes/polaris.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://polaris_ranger_ev/materials/scripts</uri>
<uri>model://polaris_ranger_ev/materials/textures</uri>
<name>Polaris/Diffuse</name>
</script>
</material>
</visual>
<collision name="chassis_bottom">
<pose>0.0 0.0 0.35 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>2.0 1.0 0.1</size>
</box>
</geometry>
</collision>
<collision name="cargo_bottom">
<pose>-0.9 0.0 0.9 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.9 1.2 0.01</size>
</box>
</geometry>
</collision>
<collision name="cargo_front">
<pose>-0.45 0.0 1.025 0.0 1.5708 0.0</pose>
<geometry>
<box>
<size>0.25 1.2 0.05</size>
</box>
</geometry>
</collision>
<collision name="cargo_back">
<pose>-1.35 0.0 1.025 0.0 1.5708 0.0</pose>
<geometry>
<box>
<size>0.25 1.2 0.05</size>
</box>
</geometry>
</collision>
<collision name="cargo_left">
<pose>-0.9 0.6 1.025 1.5708 1.5708 0.0</pose>
<geometry>
<box>
<size>0.25 0.9 0.05</size>
</box>
</geometry>
</collision>
<collision name="cargo_right">
<pose>-0.9 -0.6 1.025 1.5708 1.5708 0.0</pose>
<geometry>
<box>
<size>0.25 0.9 0.05</size>
</box>
</geometry>
</collision>
<collision name="seat">
<pose>-0.1 0.0 0.625 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.6 1.0 0.65</size>
</box>
</geometry>
</collision>
<collision name="seat_back">
<pose>-0.3 0.0 1.125 0.0 -0.2 0.0</pose>
<geometry>
<box>
<size>0.1 1.0 0.4</size>
</box>
</geometry>
</collision>
<collision name="engine">
<pose>0.95 0.0 0.7 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.75 1.0 0.8</size>
</box>
</geometry>
</collision>
<collision name="steering_column">
<pose>0.525 0.3 1.025 0.0 -0.8 0.0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.45</length>
</cylinder>
</geometry>
</collision>
<collision name="steering_wheel_post_left">
<pose>0.37 0.38 1.2 1.5708 -0.8 0.0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.15</length>
</cylinder>
</geometry>
</collision>
<collision name="steering_wheel_post_right">
<pose>0.37 0.23 1.2 1.5708 -0.8 0.0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.15</length>
</cylinder>
</geometry>
</collision>
<collision name="steering_wheel_post_middle">
<pose>0.325 0.305 1.15 0.0 -2.3708 0.0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.15</length>
</cylinder>
</geometry>
</collision>
</link>
<link name="rear_right_wheel">
<pose>-0.85 -0.675 0.3 1.5708 0.0 0.0</pose>
<inertial>
<mass>0.5</mass>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.3</radius>
<length>0.2</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<joint type="revolute" name="rear_right_wheel_joint">
<pose>0.0 0.0 -0.1 0 0 0</pose>
<child>rear_right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<link name="rear_left_wheel">
<pose>-0.85 0.575 0.3 1.5708 0.0 0.0</pose>
<inertial>
<mass>0.5</mass>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.3</radius>
<length>0.2</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<joint type="revolute" name="rear_left_wheel_joint">
<pose>0.0 0.0 0.1 0 0 0</pose>
<child>rear_left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<link name="front_right_wheel">
<pose>1.03 -0.55 0.3 1.5708 0.0 0.0</pose>
<inertial>
<mass>0.5</mass>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.3</radius>
<length>0.2</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<joint type="revolute" name="front_right_wheel_joint">
<pose>0.0 0.0 -0.1 0 0 0</pose>
<child>front_right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<link name="front_left_wheel">
<pose>1.03 0.65 0.3 1.5708 0.0 0.0</pose>
<inertial>
<mass>0.5</mass>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.3</radius>
<length>0.2</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<joint type="revolute" name="front_left_wheel_joint">
<pose>0.0 0.0 0.1 0 0 0</pose>
<child>front_left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
</model>
</sdf>