309 lines
8.7 KiB
XML
309 lines
8.7 KiB
XML
<?xml version="1.0" ?>
|
|
<sdf version="1.4">
|
|
<world name="default">
|
|
<physics type="ode">
|
|
<gravity>0.000000 0.000000 -9.810000</gravity>
|
|
<ode>
|
|
<solver>
|
|
<type>quick</type>
|
|
<iters>250</iters>
|
|
<precon_iters>0</precon_iters>
|
|
<sor>1.400000</sor>
|
|
</solver>
|
|
<constraints>
|
|
<cfm>0.000000</cfm>
|
|
<erp>0.200000</erp>
|
|
<contact_max_correcting_vel>0.000000</contact_max_correcting_vel>
|
|
<contact_surface_layer>0.00000</contact_surface_layer>
|
|
</constraints>
|
|
</ode>
|
|
<bullet>
|
|
<solver>
|
|
<type>sequential_impulse</type>
|
|
<iters>250</iters>
|
|
<sor>1.400000</sor>
|
|
</solver>
|
|
<constraints>
|
|
<cfm>0.000000</cfm>
|
|
<erp>0.200000</erp>
|
|
<split_impulse>true</split_impulse>
|
|
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
|
|
<contact_surface_layer>0.01000</contact_surface_layer>
|
|
</constraints>
|
|
</bullet>
|
|
<simbody>
|
|
<accuracy>0.001</accuracy>
|
|
<max_transient_velocity>0.01</max_transient_velocity>
|
|
<contact>
|
|
<stiffness>1e8</stiffness>
|
|
<dissipation>10</dissipation>
|
|
<static_friction>0.15</static_friction>
|
|
<dynamic_friction>0.1</dynamic_friction>
|
|
<viscous_friction>0.0</viscous_friction>
|
|
</contact>
|
|
</simbody>
|
|
<real_time_update_rate>0.000000</real_time_update_rate>
|
|
<max_step_size>0.001000</max_step_size>
|
|
</physics>
|
|
|
|
<include>
|
|
<uri>model://ground_plane</uri>
|
|
</include>
|
|
<include>
|
|
<uri>model://sun</uri>
|
|
</include>
|
|
|
|
<model name='trikey'>
|
|
<pose>0 0 0.5 0 -0 0</pose>
|
|
<link name='trikey_base'>
|
|
<pose>0 0 0 0 -0 0</pose>
|
|
<inertial>
|
|
<pose>-0.003048 0.00254 0.41415 0 -0 0</pose>
|
|
<mass>32.7</mass>
|
|
<inertia>
|
|
<ixx>1.747</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>1.747</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>1.192</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name='trikey_base_visual'>
|
|
<pose>0 0 0.426 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.65</length>
|
|
<radius>0.27</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
</visual>
|
|
<collision name='trikey_base_collision'>
|
|
<pose>0 0 0.426 0 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.65</length>
|
|
<radius>0.27</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<velocity_decay>
|
|
<linear>0</linear>
|
|
<angular>0</angular>
|
|
</velocity_decay>
|
|
</link>
|
|
<joint name='world_to_base' type='revolute'>
|
|
<child>trikey_base</child>
|
|
<parent>world</parent>
|
|
<axis>
|
|
<limit>
|
|
<lower>0</lower>
|
|
<upper>0</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<damping>0</damping>
|
|
</dynamics>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
<link name='ow_transform_0_l'>
|
|
<pose>0 -0.24 0.1 0 -0 0</pose>
|
|
<inertial>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<mass>0.66725</mass>
|
|
<inertia>
|
|
<ixx>0.00160418</ixx>
|
|
<ixy>-3.598e-06</ixy>
|
|
<ixz>1.6199e-05</ixz>
|
|
<iyy>0.00279814</iyy>
|
|
<iyz>-4.1656e-05</iyz>
|
|
<izz>0.00160339</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='ow_transform_0_l_collision_omni_wheel_0'>
|
|
<pose>0 -0.05 2.44839e-13 1.5708 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.025</length>
|
|
<radius>0.101</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode/>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name='ow_transform_0_l_visual_omni_wheel_0'>
|
|
<pose>0 -0.05 2.44839e-13 1.5708 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.025</length>
|
|
<radius>0.101</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Red</name>
|
|
<uri>__default__</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay>
|
|
<linear>0</linear>
|
|
<angular>0</angular>
|
|
</velocity_decay>
|
|
<self_collide>0</self_collide>
|
|
</link>
|
|
<joint name='wheel1_joint' type='revolute'>
|
|
<child>ow_transform_0_l</child>
|
|
<parent>trikey_base</parent>
|
|
<axis>
|
|
<xyz>0 -1 0</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics/>
|
|
</axis>
|
|
</joint>
|
|
<link name='ow_transform_1_l'>
|
|
<pose>0.207846 0.12 0.1 0 -0 2.0944</pose>
|
|
<inertial>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<mass>0.66725</mass>
|
|
<inertia>
|
|
<ixx>0.00160418</ixx>
|
|
<ixy>-3.598e-06</ixy>
|
|
<ixz>1.6199e-05</ixz>
|
|
<iyy>0.00279814</iyy>
|
|
<iyz>-4.1656e-05</iyz>
|
|
<izz>0.00160339</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='ow_transform_1_l_collision_omni_wheel_1'>
|
|
<pose>0 -0.05 2.44839e-13 1.5708 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.025</length>
|
|
<radius>0.101</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode/>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name='ow_transform_1_l_visual_omni_wheel_1'>
|
|
<pose>0 -0.05 2.44839e-13 1.5708 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.025</length>
|
|
<radius>0.101</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Green</name>
|
|
<uri>__default__</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay>
|
|
<linear>0</linear>
|
|
<angular>0</angular>
|
|
</velocity_decay>
|
|
<self_collide>0</self_collide>
|
|
</link>
|
|
<joint name='wheel2_joint' type='revolute'>
|
|
<child>ow_transform_1_l</child>
|
|
<parent>trikey_base</parent>
|
|
<axis>
|
|
<xyz>0.866025 0.5 0</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics/>
|
|
</axis>
|
|
</joint>
|
|
<link name='ow_transform_2_l'>
|
|
<pose>-0.207846 0.12 0.1 0 0 -2.0944</pose>
|
|
<inertial>
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<mass>0.66725</mass>
|
|
<inertia>
|
|
<ixx>0.00160418</ixx>
|
|
<ixy>-3.598e-06</ixy>
|
|
<ixz>1.6199e-05</ixz>
|
|
<iyy>0.00279814</iyy>
|
|
<iyz>-4.1656e-05</iyz>
|
|
<izz>0.00160339</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='ow_transform_2_l_collision_omni_wheel_2'>
|
|
<pose>0 -0.05 2.44839e-13 1.5708 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.025</length>
|
|
<radius>0.101</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode/>
|
|
</contact>
|
|
<friction>
|
|
<ode/>
|
|
</friction>
|
|
</surface>
|
|
</collision>
|
|
<visual name='ow_transform_2_l_visual_omni_wheel_2'>
|
|
<pose>0 -0.05 2.44839e-13 1.5708 -0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<length>0.025</length>
|
|
<radius>0.101</radius>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<script>
|
|
<name>Gazebo/Blue</name>
|
|
<uri>__default__</uri>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
<gravity>1</gravity>
|
|
<velocity_decay>
|
|
<linear>0</linear>
|
|
<angular>0</angular>
|
|
</velocity_decay>
|
|
<self_collide>0</self_collide>
|
|
</link>
|
|
<joint name='wheel3_joint' type='revolute'>
|
|
<child>ow_transform_2_l</child>
|
|
<parent>trikey_base</parent>
|
|
<axis>
|
|
<xyz>-0.866025 0.5 0</xyz>
|
|
<limit>
|
|
<lower>-1e+16</lower>
|
|
<upper>1e+16</upper>
|
|
</limit>
|
|
<dynamics/>
|
|
</axis>
|
|
</joint>
|
|
<static>0</static>
|
|
</model>
|
|
</world>
|
|
</sdf>
|
|
|