init
This commit is contained in:
220
pioneer3at/model-1_4.sdf
Normal file
220
pioneer3at/model-1_4.sdf
Normal file
@@ -0,0 +1,220 @@
|
||||
<?xml version='1.0'?>
|
||||
<sdf version="1.4">
|
||||
<model name="pioneer3at">
|
||||
<pose>0 0 0.180 0 0 0</pose>
|
||||
<static>false</static>
|
||||
|
||||
<link name="chassis">
|
||||
<inertial>
|
||||
<mass>14.0</mass>
|
||||
<inertia>
|
||||
<!-- http://en.wikipedia.org/wiki/List_of_moment_of_inertia_tensors
|
||||
MATLAB:
|
||||
m=14; h=0.19; w=0.4; d=0.5;
|
||||
ixx = 1/12*m*(h^2+d^2)
|
||||
iyy = 1/12*m*(w^2+d^2)
|
||||
izz = 1/12*m*(h^2+d^2)
|
||||
-->
|
||||
<ixx>0.3338</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyy>0.4783</iyy>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.3338</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.501 0.400 0.19</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://pioneer3at/meshes/chassis.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="right_front_wheel">
|
||||
<pose>0.125 -0.201 -0.06 1.5707 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.110</radius>
|
||||
<length>0.075</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1</mu>
|
||||
<mu2>1</mu2>
|
||||
<slip1>0.5</slip1>
|
||||
<slip2>0</slip2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://pioneer3at/meshes/wheel.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="left_front_wheel">
|
||||
<pose>0.125 0.201 -0.06 1.5707 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.110</radius>
|
||||
<length>0.075</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1</mu>
|
||||
<mu2>1</mu2>
|
||||
<slip1>0.5</slip1>
|
||||
<slip2>0</slip2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://pioneer3at/meshes/wheel.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="right_rear_wheel">
|
||||
<pose>-0.125 -0.201 -0.06 1.5707 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.110</radius>
|
||||
<length>0.075</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1</mu>
|
||||
<mu2>1</mu2>
|
||||
<slip1>0.5</slip1>
|
||||
<slip2>0</slip2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://pioneer3at/meshes/wheel.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="left_rear_wheel">
|
||||
<pose>-0.125 0.201 -0.06 1.5707 0 0</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.110</radius>
|
||||
<length>0.075</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>1</mu>
|
||||
<mu2>1</mu2>
|
||||
<slip1>0.5</slip1>
|
||||
<slip2>0</slip2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://pioneer3at/meshes/wheel.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
|
||||
<joint type="revolute" name="right_front">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<child>right_front_wheel</child>
|
||||
<parent>chassis</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint type="revolute" name="right_rear">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<child>right_rear_wheel</child>
|
||||
<parent>chassis</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint type="revolute" name="left_front">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<child>left_front_wheel</child>
|
||||
<parent>chassis</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint type="revolute" name="left_rear">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<child>left_rear_wheel</child>
|
||||
<parent>chassis</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<plugin name="SkidSteerDrivePlugin" filename="libSkidSteerDrivePlugin.so">
|
||||
<right_front>right_front</right_front>
|
||||
<right_rear>right_rear</right_rear>
|
||||
<left_front>left_front</left_front>
|
||||
<left_rear>left_rear</left_rear>
|
||||
<MaxForce>5.0</MaxForce>
|
||||
</plugin>
|
||||
|
||||
<!--
|
||||
<include>
|
||||
<uri>model://hokuyo</uri>
|
||||
<pose>0.2 0 0.13 0 0 0</pose>
|
||||
</include>
|
||||
<joint name="hokuyo_joint" type="revolute">
|
||||
<child>hokuyo::link</child>
|
||||
<parent>chassis</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<upper>0</upper>
|
||||
<lower>0</lower>
|
||||
</limit>
|
||||
</axis>
|
||||
</joint>
|
||||
-->
|
||||
|
||||
|
||||
</model>
|
||||
</sdf>
|
Reference in New Issue
Block a user