593 lines
17 KiB
Plaintext
593 lines
17 KiB
Plaintext
![]() |
<?xml version="1.0"?>
|
||
|
<sdf version="1.3">
|
||
|
<model name="polaris_ranger_ev">
|
||
|
<link name="chassis">
|
||
|
<inertial>
|
||
|
<!-- subtracted wheel weights from dry weight of 771 kg -->
|
||
|
<!-- http://www.polaris.com/en-us/ranger-utv/side-by-sides/ranger-ev/specifications -->
|
||
|
<mass>720.0</mass>
|
||
|
<inertia>
|
||
|
<ixx>140</ixx>
|
||
|
<ixy>0.0</ixy><iyy>550</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>550</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<visual name="visual">
|
||
|
<!-- rotate mesh to get to X-forward -->
|
||
|
<pose>0 0 0 0 0 -1.570796</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 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.05 1.2 0.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision name="cargo_back">
|
||
|
<pose>-1.35 0.0 1.025 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.05 1.2 0.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision name="cargo_left">
|
||
|
<pose>-0.9 0.6 1.025 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.9 0.05 0.25</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision name="cargo_right">
|
||
|
<pose>-0.9 -0.6 1.025 0.0 0.0 0.0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.9 0.05 0.25</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.58 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>
|
||
|
</link>
|
||
|
<link name="rear_right_wheel">
|
||
|
<pose>-0.85 -0.6 0.32 1.570796 0.0 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||
|
<inertia>
|
||
|
<ixx>0.5</ixx>
|
||
|
<ixy>0.0</ixy><iyy>0.5</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.32</radius>
|
||
|
<length>0.23</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>
|
||
|
<physics><ode><limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit></ode></physics>
|
||
|
</joint>
|
||
|
<link name="rear_left_wheel">
|
||
|
<pose>-0.85 0.6 0.32 1.570796 0.0 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||
|
<inertia>
|
||
|
<ixx>0.5</ixx>
|
||
|
<ixy>0.0</ixy><iyy>0.5</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.32</radius>
|
||
|
<length>0.23</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">
|
||
|
<child>rear_left_wheel</child>
|
||
|
<parent>chassis</parent>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
</axis>
|
||
|
<physics><ode><limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit></ode></physics>
|
||
|
</joint>
|
||
|
<link name="front_right_wheel">
|
||
|
<pose>1.03 -0.6 0.32 1.570796 0.0 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||
|
<inertia>
|
||
|
<ixx>0.5</ixx>
|
||
|
<ixy>0.0</ixy><iyy>0.5</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.32</radius>
|
||
|
<length>0.23</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>
|
||
|
<link name="front_right_wheel_steering_block">
|
||
|
<pose>1.03 -0.5 0.32 1.570796 0.0 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>1</mass>
|
||
|
<inertia>
|
||
|
<ixx>1.0</ixx>
|
||
|
<ixy>0.0</ixy><iyy>1.0</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.05</radius>
|
||
|
<length>0.01</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint type="revolute" name="front_right_steering_joint">
|
||
|
<child>front_right_wheel_steering_block</child>
|
||
|
<parent>chassis</parent>
|
||
|
<axis>
|
||
|
<xyz>0 0 1</xyz>
|
||
|
<limit>
|
||
|
<lower>-1.0</lower>
|
||
|
<upper>1.0</upper>
|
||
|
</limit>
|
||
|
</axis>
|
||
|
<physics><ode><limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit></ode></physics>
|
||
|
</joint>
|
||
|
<joint type="revolute" name="front_right_wheel_joint">
|
||
|
<child>front_right_wheel</child>
|
||
|
<parent>front_right_wheel_steering_block</parent>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
</axis>
|
||
|
<physics><ode><limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit></ode></physics>
|
||
|
</joint>
|
||
|
<link name="front_left_wheel">
|
||
|
<pose>1.03 0.6 0.32 1.570796 0.0 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>12</mass><!-- estimated from http://www.rzrforums.net/wheels-tires/1729-tire-wheel-weights-most-sizes.html -->
|
||
|
<inertia>
|
||
|
<ixx>0.5</ixx>
|
||
|
<ixy>0.0</ixy><iyy>0.5</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.32</radius>
|
||
|
<length>0.23</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>
|
||
|
<link name="front_left_wheel_steering_block">
|
||
|
<pose>1.03 0.5 0.32 1.570796 0.0 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>1</mass>
|
||
|
<inertia>
|
||
|
<ixx>1.0</ixx>
|
||
|
<ixy>0.0</ixy><iyy>1.0</iyy>
|
||
|
<ixz>0.0</ixz><iyz>0.0</iyz><izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.05</radius>
|
||
|
<length>0.01</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint type="revolute" name="front_left_steering_joint">
|
||
|
<child>front_left_wheel_steering_block</child>
|
||
|
<parent>chassis</parent>
|
||
|
<axis>
|
||
|
<xyz>0 0 1</xyz>
|
||
|
<limit>
|
||
|
<lower>-1.0</lower>
|
||
|
<upper>1.0</upper>
|
||
|
</limit>
|
||
|
</axis>
|
||
|
<physics><ode><limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit></ode></physics>
|
||
|
</joint>
|
||
|
<joint type="revolute" name="front_left_wheel_joint">
|
||
|
<child>front_left_wheel</child>
|
||
|
<parent>front_left_wheel_steering_block</parent>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
</axis>
|
||
|
<physics><ode><limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit></ode></physics>
|
||
|
</joint>
|
||
|
<!-- gas/brake pedals, steering wheel and hand brake -->
|
||
|
<link name='gas_pedal'>
|
||
|
<pose>0.53 0.14 0.56 0 -1.0 0</pose>
|
||
|
<gravity>false</gravity>
|
||
|
<inertial>
|
||
|
<mass>0.1</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.01</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.01</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.01</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name='gas_pedal_collision'>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.120000 0.070000 0.030000</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name='gas_pedal_visual'>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.120000 0.070000 0.030000</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/Wood</name>
|
||
|
</script>
|
||
|
<ambient>0.2 0.2 0.2 1</ambient>
|
||
|
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||
|
<specular>0.2 0.2 0.2 1</specular>
|
||
|
<emissive>0.5 0.5 0.5 1</emissive>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
|
||
|
<link name='brake_pedal'>
|
||
|
<gravity>false</gravity>
|
||
|
<pose>0.54 0.27 0.58 0 -1.0 0</pose>
|
||
|
<inertial>
|
||
|
<mass>0.1</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.01</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.01</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.01</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name='brake_pedal_collision'>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.06 0.08 0.03</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name='brake_pedal_visual'>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.060000 0.080000 0.030000</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/Wood</name>
|
||
|
</script>
|
||
|
<ambient>0.2 0.2 0.2 1</ambient>
|
||
|
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||
|
<specular>0.2 0.2 0.2 1</specular>
|
||
|
<emissive>0.5 0.5 0.5 1</emissive>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
|
||
|
<link name='steering_wheel'>
|
||
|
<pose>0.37 0.30 1.2 0 -0.8 0</pose>
|
||
|
<inertial>
|
||
|
<mass>1.0</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.1</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.1</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="steering_wheel_post_left">
|
||
|
<pose>0.0 0.08 0.0 1.570796 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.02</radius>
|
||
|
<length>0.15</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision name="steering_wheel_post_right">
|
||
|
<pose>0.0 -0.08 0.0 1.570796 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.02</radius>
|
||
|
<length>0.15</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision name="steering_wheel_post_middle">
|
||
|
<pose>-0.08 0.0 0.0 0 1.570796 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.02</radius>
|
||
|
<length>0.15</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision name="collision00">
|
||
|
<pose>0.150000 0.000000 0 0 1.570796 1.570796</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision01">
|
||
|
<pose>0.121353 0.088168 0 0 1.570796 2.199115</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision02">
|
||
|
<pose>0.046353 0.142658 0 0 1.570796 2.827433</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision03">
|
||
|
<pose>-0.046353 0.142658 0 0 1.570796 3.455752</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision04">
|
||
|
<pose>-0.121353 0.088168 0 0 1.570796 4.084070</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision05">
|
||
|
<pose>-0.150000 0.000000 0 0 1.570796 4.712389</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision06">
|
||
|
<pose>-0.121353 -0.088168 0 0 1.570796 5.340708</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision07">
|
||
|
<pose>-0.046353 -0.142658 0 0 1.570796 5.969026</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision08">
|
||
|
<pose>0.046353 -0.142658 0 0 1.570796 6.597345</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
<collision name="collision09">
|
||
|
<pose>0.121353 -0.088168 0 0 1.570796 7.225663</pose>
|
||
|
<geometry><cylinder><length>0.105065778087</length><radius>0.01</radius></cylinder></geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<link name='hand_brake'>
|
||
|
<pose>0.50 0.00 1.05 0.0 3.2 0.0</pose>
|
||
|
<inertial>
|
||
|
<mass>1.0</mass>
|
||
|
<pose>0 0 -0.15 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.1</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.1</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>1.0</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="hand_brake_collision">
|
||
|
<pose>0 0 -0.10 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.01</radius>
|
||
|
<length>0.2</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="hand_brake_visual">
|
||
|
<pose>0 0 -0.10 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.01</radius>
|
||
|
<length>0.2</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/Wood</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name='gas_joint' type='prismatic'>
|
||
|
<parent>chassis</parent>
|
||
|
<child>gas_pedal</child>
|
||
|
<axis>
|
||
|
<xyz>1.000000 0.000000 -1.000000</xyz>
|
||
|
<limit>
|
||
|
<lower>0.00</lower>
|
||
|
<upper>0.15</upper>
|
||
|
</limit>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name='brake_joint' type='prismatic'>
|
||
|
<parent>chassis</parent>
|
||
|
<child>brake_pedal</child>
|
||
|
<axis>
|
||
|
<xyz>1.000000 0.000000 -0.600000</xyz>
|
||
|
<limit>
|
||
|
<lower>0.00</lower>
|
||
|
<upper>0.15</upper>
|
||
|
</limit>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name='steering_joint' type='revolute'>
|
||
|
<pose>0 0 0 1.570796 -0.8 0.0</pose>
|
||
|
<parent>chassis</parent>
|
||
|
<child>steering_wheel</child>
|
||
|
<axis>
|
||
|
<xyz>-1 0 1.023</xyz>
|
||
|
<limit>
|
||
|
<lower>-7.853000</lower>
|
||
|
<upper>7.853000</upper>
|
||
|
</limit>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<joint name='hand_brake_joint' type='revolute'>
|
||
|
<parent>chassis</parent>
|
||
|
<child>hand_brake</child>
|
||
|
<axis>
|
||
|
<xyz>0.0 -1.0 0.0</xyz>
|
||
|
<limit>
|
||
|
<lower>0</lower>
|
||
|
<upper>0.6</upper>
|
||
|
</limit>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
</model>
|
||
|
</sdf>
|