mirror of
https://gitlab.com/yikestone/qt_pi.git
synced 2025-08-03 13:44:12 +05:30
182 lines
4.5 KiB
XML
182 lines
4.5 KiB
XML
<?xml version="1.0"?>
|
|
<sdf version="1.4">
|
|
<model name="pioneer2dx">
|
|
<link name="chassis">
|
|
<pose>0 0 0.16 0 0 0</pose>
|
|
<inertial>
|
|
<mass>5.67</mass>
|
|
<inertia>
|
|
<ixx>0.07</ixx>
|
|
<iyy>0.08</iyy>
|
|
<izz>0.10</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<box>
|
|
<size>0.445 0.277 0.17</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
<collision name="castor_collision">
|
|
<pose>-0.200 0 -0.12 0 0 0</pose>
|
|
<geometry>
|
|
<sphere>
|
|
<radius>0.04</radius>
|
|
</sphere>
|
|
</geometry>
|
|
<surface>
|
|
<friction>
|
|
<ode>
|
|
<mu>0</mu>
|
|
<mu2>0</mu2>
|
|
<slip1>1.0</slip1>
|
|
<slip2>1.0</slip2>
|
|
</ode>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name="visual">
|
|
<pose>0 0 0.04 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://pioneer2dx/meshes/chassis.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
<visual name="castor_visual">
|
|
<pose>-0.200 0 -0.12 0 0 0</pose>
|
|
<geometry>
|
|
<sphere>
|
|
<radius>0.04</radius>
|
|
</sphere>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/FlatBlack</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="right_wheel">
|
|
<pose>0.1 -.17 0.11 0 1.5707 1.5707</pose>
|
|
<inertial>
|
|
<mass>1.5</mass>
|
|
<inertia>
|
|
<ixx>0.0051</ixx>
|
|
<iyy>0.0051</iyy>
|
|
<izz>0.0090</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.11</radius>
|
|
<length>0.05</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>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.11</radius>
|
|
<length>0.05</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/FlatBlack</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<link name="left_wheel">
|
|
<pose>0.1 .17 0.11 0 1.5707 1.5707</pose>
|
|
<inertial>
|
|
<mass>1.5</mass>
|
|
<inertia>
|
|
<ixx>0.0051</ixx>
|
|
<iyy>0.0051</iyy>
|
|
<izz>0.0090</izz>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyz>0</iyz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.11</radius>
|
|
<length>0.05</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>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.11</radius>
|
|
<length>0.05</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
|
<name>Gazebo/FlatBlack</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint type="revolute" name="left_wheel_hinge">
|
|
<pose>0 0 -0.03 0 0 0</pose>
|
|
<child>left_wheel</child>
|
|
<parent>chassis</parent>
|
|
<axis>
|
|
<xyz>0 1 0</xyz>
|
|
</axis>
|
|
</joint>
|
|
<joint type="revolute" name="right_wheel_hinge">
|
|
<pose>0 0 0.03 0 0 0</pose>
|
|
<child>right_wheel</child>
|
|
<parent>chassis</parent>
|
|
<axis>
|
|
<xyz>0 1 0</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<plugin filename="libDiffDrivePlugin.so" name="diff_drive">
|
|
<left_joint>left_wheel_hinge</left_joint>
|
|
<right_joint>right_wheel_hinge</right_joint>
|
|
<torque>5</torque>
|
|
</plugin>
|
|
|
|
</model>
|
|
</sdf>
|