270 lines
7.9 KiB
XML
270 lines
7.9 KiB
XML
<?xml version="1.0" ?>
|
|
<sdf version="1.3">
|
|
<model name="car">
|
|
<link name="chassis">
|
|
<pose>0 0 0.3 0 0 0</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<box><size>2.0 1.0 0.2</size></box>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<box><size>2.0 1.0 0.2</size></box>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Green</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="front_left_wheel">
|
|
<pose>0.8 0.6 0.3 0 1.5707 1.5707</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="front_right_wheel">
|
|
<pose>0.8 -0.6 0.3 0 1.5707 1.5707</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="back_right_wheel">
|
|
<pose>-0.8 -0.6 0.3 0 1.5707 1.5707</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="back_left_wheel">
|
|
<pose>-0.8 0.6 0.3 0 1.5707 1.5707</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="gas_pedal">
|
|
<pose>0.3 0.1 0.5 0 0 0</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<box><size>0.1 0.1 0.1</size></box>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<box><size>0.1 0.1 0.1</size></box>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Red</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="brake_pedal">
|
|
<pose>0.3 0.25 0.5 0 0 0</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<box><size>0.1 0.1 0.1</size></box>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<box><size>0.1 0.1 0.1</size></box>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Blue</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="steering_wheel">
|
|
<pose>0.3 0.2 1.0 0 1.5707 0</pose>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder><radius>0.1</radius><length>0.01</length></cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder><radius>0.1</radius><length>0.01</length></cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Blue</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint type="prismatic" name="gas_joint">
|
|
<parent>chassis</parent>
|
|
<child>gas_pedal</child>
|
|
<axis>
|
|
<xyz>1 0 0</xyz>
|
|
<limit><lower>0</lower><upper>0.2</upper></limit>
|
|
</axis>
|
|
</joint>
|
|
<joint type="prismatic" name="brake_joint">
|
|
<parent>chassis</parent>
|
|
<child>brake_pedal</child>
|
|
<axis>
|
|
<xyz>1 0 0</xyz>
|
|
<limit><lower>0</lower><upper>0.2</upper></limit>
|
|
</axis>
|
|
</joint>
|
|
<joint type="revolute" name="steering_joint">
|
|
<parent>chassis</parent>
|
|
<child>steering_wheel</child>
|
|
<axis>
|
|
<xyz>1 0 0</xyz>
|
|
<limit><lower>-7.853</lower><upper>7.853</upper></limit>
|
|
</axis>
|
|
</joint>
|
|
<joint type="revolute2" name="front_left_joint">
|
|
<parent>chassis</parent>
|
|
<child>front_left_wheel</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
<limit>
|
|
<lower>0</lower>
|
|
<upper>0</upper>
|
|
</limit>
|
|
</axis>
|
|
<axis2>
|
|
<xyz>0 1 0</xyz>
|
|
</axis2>
|
|
<physics>
|
|
<ode>
|
|
<limit><cfm>0.0</cfm><erp>0.9</erp></limit>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
<joint type="revolute2" name="front_right_joint">
|
|
<parent>chassis</parent>
|
|
<child>front_right_wheel</child>
|
|
<axis><xyz>0 0 1</xyz>
|
|
<limit><lower>0</lower><upper>0</upper></limit>
|
|
</axis>
|
|
<axis2>
|
|
<xyz>0 1 0</xyz>
|
|
</axis2>
|
|
<physics>
|
|
<ode>
|
|
<limit><cfm>0.0</cfm><erp>0.9</erp></limit>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
<joint type="revolute2" name="back_right_joint">
|
|
<parent>chassis</parent>
|
|
<child>back_right_wheel</child>
|
|
<axis><xyz>0 0 1</xyz>
|
|
<limit><lower>0</lower><upper>0</upper></limit>
|
|
</axis>
|
|
<axis2>
|
|
<xyz>0 1 0</xyz>
|
|
</axis2>
|
|
<physics>
|
|
<ode>
|
|
<limit><cfm>0.0</cfm><erp>0.9</erp></limit>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
<joint type="revolute2" name="back_left_joint">
|
|
<parent>chassis</parent>
|
|
<child>back_left_wheel</child>
|
|
<axis><xyz>0 0 1</xyz>
|
|
<limit><lower>0</lower><upper>0</upper></limit>
|
|
</axis>
|
|
<axis2>
|
|
<xyz>0 1 0</xyz>
|
|
</axis2>
|
|
<physics>
|
|
<ode>
|
|
<limit><cfm>0.0</cfm><erp>0.9</erp></limit>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
|
|
<plugin filename="libVehiclePlugin.so" name="vehicle">
|
|
<!-- Joints for each wheel -->
|
|
<front_left>front_left_joint</front_left>
|
|
<front_right>front_right_joint</front_right>
|
|
<back_left>back_left_joint</back_left>
|
|
<back_right>back_right_joint</back_right>
|
|
<!-- Joint which controls the gas -->
|
|
<gas>gas_joint</gas>
|
|
<!-- Joint which controls the gas -->
|
|
<brake>brake_joint</brake>
|
|
<!-- Joint which controls the steering -->
|
|
<steering>steering_joint</steering>
|
|
<!-- Power is multiplied by "gas" to determine force applied to wheels -->
|
|
<front_power>10</front_power>
|
|
<rear_power>10</rear_power>
|
|
<!-- The angle range the front tires can turn for steering, in radians -->
|
|
<tire_angle_range>0.5</tire_angle_range>
|
|
<!-- Maximum speed for the car in meters/second -->
|
|
<max_speed>10</max_speed>
|
|
<!-- Factor for the down-force applied as the car travels faster -->
|
|
<!-- A larger number increases the down force -->
|
|
<aero_load>0.1</aero_load>
|
|
</plugin>
|
|
</model>
|
|
</sdf>
|