219 lines
5.5 KiB
XML
219 lines
5.5 KiB
XML
<?xml version="1.0" ?>
|
|
|
|
<sdf version="1.5">
|
|
<model name="cart_rigid_suspension">
|
|
<link name="chassis">
|
|
<pose>0 0 0.15 0 0 0</pose>
|
|
<inertial>
|
|
<pose>0.1 0 0 0 0 0</pose>
|
|
<mass>10</mass>
|
|
<inertia>
|
|
<ixx>0.21666666666666667</ixx>
|
|
<iyy>0.8416666666666667</iyy>
|
|
<izz>1.0416666666666667</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<box>
|
|
<size>1.0 0.5 0.1</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<box>
|
|
<size>1.0 0.5 0.1</size>
|
|
</box>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Grey</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
|
|
<link name="wheel_front_left">
|
|
<pose>0.5 0.298 0.15 -1.5707963267948966 0 0</pose>
|
|
<inertial>
|
|
<mass>0.5</mass>
|
|
<inertia>
|
|
<ixx>0.0030791666666666667</ixx>
|
|
<iyy>0.0030791666666666667</iyy>
|
|
<izz>0.005625</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name="wheel_front_left_spin" type="revolute">
|
|
<parent>chassis</parent>
|
|
<child>wheel_front_left</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<link name="wheel_front_right">
|
|
<pose>0.5 -0.298 0.15 -1.5707963267948966 0 0</pose>
|
|
<inertial>
|
|
<mass>0.5</mass>
|
|
<inertia>
|
|
<ixx>0.0030791666666666667</ixx>
|
|
<iyy>0.0030791666666666667</iyy>
|
|
<izz>0.005625</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name="wheel_front_right_spin" type="revolute">
|
|
<parent>chassis</parent>
|
|
<child>wheel_front_right</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<link name="wheel_rear_left">
|
|
<pose>-0.5 0.298 0.15 -1.5707963267948966 0 0</pose>
|
|
<inertial>
|
|
<mass>0.5</mass>
|
|
<inertia>
|
|
<ixx>0.0030791666666666667</ixx>
|
|
<iyy>0.0030791666666666667</iyy>
|
|
<izz>0.005625</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name="wheel_rear_left_spin" type="revolute">
|
|
<parent>chassis</parent>
|
|
<child>wheel_rear_left</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<link name="wheel_rear_right">
|
|
<pose>-0.5 -0.298 0.15 -1.5707963267948966 0 0</pose>
|
|
<inertial>
|
|
<mass>0.5</mass>
|
|
<inertia>
|
|
<ixx>0.0030791666666666667</ixx>
|
|
<iyy>0.0030791666666666667</iyy>
|
|
<izz>0.005625</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.15</radius>
|
|
<length>0.08</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/Black</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name="wheel_rear_right_spin" type="revolute">
|
|
<parent>chassis</parent>
|
|
<child>wheel_rear_right</child>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
</model>
|
|
</sdf>
|