ppovb5fc7/gazebo/test/worlds/spring_damper_test.world

809 lines
23 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<scene>
<ambient>0.5 0.5 0.5 1</ambient>
<background>0.5 0.5 0.5 1</background>
<shadows>false</shadows>
</scene>
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<physics type="ode">
<gravity>0.0 0.0 -10.0</gravity>
<ode>
<solver>
<type>quick</type>
<iters>100</iters>
<sor>1.3</sor>
</solver>
<constraints>
<cfm>0.0</cfm>
<erp>1.0</erp>
<contact_max_correcting_vel>10000.0</contact_max_correcting_vel>
<contact_surface_layer>0.0</contact_surface_layer>
</constraints>
</ode>
<simbody>
<accuracy>0.01</accuracy>
<max_transient_velocity>0.01</max_transient_velocity>
<contact>
<stiffness>111.111</stiffness>
<dissipation>0</dissipation>
</contact>
</simbody>
<real_time_update_rate>0</real_time_update_rate>
<max_step_size>0.001</max_step_size>
</physics>
<!-- a test of spring, see reference from ODE discussion
http://www.ode.org/old_list_archives/2006-March/018014.html
where stiffness and damping are related to joint limit cfm and erp
public static void Calc(float springConstant, float dampingCofficient, float
sprungMass, out float erp, out float cfm)
{
float r = 2.0f * dampingCofficient * (float)Math.Sqrt(sprungMass
* springConstant);
float hk = Scene.OdeTimeStep * springConstant;
erp = hk / (hk + r);
cfm = 1.0f / (hk + r);
}
in the end,
erp = dt * kp / ( dt * kp + kd )
cfm = 1 / ( dt * kp + kd )
or
kp = erp / (cfm * h)
kd = (1 - erp) / cfm
-->
<model name="model_0">
<pose>0.0 0.0 1.1 0 0.0 0.0</pose>
<link name="link_1">
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Grey</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="prismatic">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
<stiffness>1.0e6</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>0.0</cfm>
<erp>0.2</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_1_prismatic">
<pose>0.0 0.3 1.1 0 0.0 0.0</pose>
<link name="link_1">
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/White</name></script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="prismatic">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0.0</lower>
<upper>0.0</upper>
<stiffness>333.3333</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>3.0</cfm>
<erp>1.0</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_1_revolute">
<pose>-1.0 0.3 1.1 0 0.0 0.0</pose>
<link name="link_1">
<velocity_decay>
<linear>0.0</linear>
<angular>0.0</angular>
</velocity_decay>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.0001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0001</iyy>
<iyz>0.0</iyz>
<izz>0.0001</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/White</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="revolute">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0.0</lower>
<upper>0.0</upper>
<stiffness>333.3333</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 1.0 0.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>3.0</cfm>
<erp>1.0</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_2_prismatic">
<pose>0.0 0.6 1.1 0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/FlatBlack</name></script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="prismatic">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
<stiffness>166.66667</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>6.0</cfm>
<erp>1.0</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_2_revolute">
<pose>-1.0 0.6 1.1 0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/FlatBlack</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="revolute">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
<stiffness>166.66667</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 1.0 0.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>6.0</cfm>
<erp>1.0</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_3_prismatic">
<pose>0.0 0.9 1.1 0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="prismatic">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
<stiffness>111.1111</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>9.0</cfm>
<erp>1.0</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_3_revolute">
<pose>-1.0 0.9 1.1 0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>1.0 0.0 0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="revolute">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
<stiffness>111.1111</stiffness>
<dissipation>0</dissipation>
</limit>
<xyz>0.0 1.0 0.0</xyz>
</axis>
<physics>
<ode>
<limit>
<cfm>9.0</cfm>
<erp>1.0</erp>
</limit>
</ode>
</physics>
</joint>
<static>false</static>
</model>
<model name="model_4_prismatic_plugin">
<pose>0.0 1.2 1.1 0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_0" type="prismatic">
<parent>world</parent>
<child>link_1</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1.0</lower>
<upper>1.0</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
</joint>
<link name="link_2">
<pose>0.0 0.0 0.5 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 -0.5 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<joint name="joint_1" type="prismatic">
<parent>world</parent>
<child>link_2</child>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<axis>
<limit>
<lower>-1.0</lower>
<upper>1.0</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
</joint>
<plugin name="spring_test" filename="libSpringTestPlugin.so">
<joint_explicit>joint_0</joint_explicit>
<kp_explicit>111.1111</kp_explicit>
<kd_explicit>0</kd_explicit>
<joint_implicit>joint_1</joint_implicit>
<kp_implicit>111.1111</kp_implicit>
<kd_implicit>0</kd_implicit>
</plugin>
<static>false</static>
</model>
<model name="model_5_soft_contact">
<pose>0.0 1.2 0.0 0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.05 0.0 0.0 0.0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>0.0 0.0 0.1 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Blue</name></script>
</material>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 0.1 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0.2</mu>
<mu2>0.2</mu2>
<fdir1>1.0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<contact>
<ode>
<kp>111.1111</kp>
<kd>0.0</kd>
<max_vel>10000.0</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
<gravity>true</gravity>
<self_collide>true</self_collide>
<kinematic>false</kinematic>
</link>
<static>false</static>
</model>
<model name="model_6_prismatic_sdf">
<pose>0.0 1.5 0.6 0 0 0</pose>
<link name="link">
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script>
</material>
</visual>
<collision name="collision">
<geometry>
<cylinder>
<length>0.1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
</collision>
</link>
<joint name="joint" type="prismatic">
<parent>world</parent>
<child>link</child>
<pose>0.0 0.0 0.5 0 0 0</pose>
<axis>
<limit>
<lower>-1.0</lower>
<upper>1.0</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
<dynamics>
<spring_stiffness>111.1111</spring_stiffness>
<spring_reference>0.0</spring_reference>
<damping>0.0</damping>
</dynamics>
</axis>
</joint>
</model>
<model name="model_7_revolute_sdf">
<pose>-1.0 1.5 0.6 0 0 0</pose>
<link name="link">
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<visual name="visual">
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
<material>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/FlatBlack</name></script>
</material>
</visual>
<collision name="collision">
<geometry>
<sphere>
<radius>0.1</radius>
</sphere>
</geometry>
</collision>
</link>
<joint name="joint" type="revolute">
<parent>world</parent>
<child>link</child>
<pose>-1.0 0.0 0.0 0 0 0</pose>
<axis>
<limit>
<lower>-10</lower>
<upper>10</upper>
</limit>
<xyz>0.0 1.0 0.0</xyz>
<dynamics>
<spring_stiffness>111.1111</spring_stiffness>
<spring_reference>0.0</spring_reference>
<damping>0.0</damping>
</dynamics>
</axis>
</joint>
</model>
</world>
</sdf>