192 lines
5.7 KiB
Plaintext
192 lines
5.7 KiB
Plaintext
![]() |
<?xml version='1.0'?>
|
||
|
<sdf version='1.6'>
|
||
|
<model name='demo_joint_stiffness'>
|
||
|
<pose>0 0 0.06 0 0 0</pose>
|
||
|
<link name='link_base'>
|
||
|
<inertial>
|
||
|
<mass>100</mass>
|
||
|
<inertia>
|
||
|
<ixx>1.2</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>3.64</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>4.6</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<gravity>1</gravity>
|
||
|
<self_collide>0</self_collide>
|
||
|
<kinematic>0</kinematic>
|
||
|
<enable_wind>0</enable_wind>
|
||
|
<visual name='visual_base'>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://demo_joint_stiffness/meshes/base_model.dae</uri>
|
||
|
<scale>0.001 0.001 0.001</scale>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
</visual>
|
||
|
<collision name='collision_base'>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>0.65 0.36 0.12</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<link name='link_high_stiffness'>
|
||
|
<gravity>0</gravity>
|
||
|
<pose>0.12 0 0.15 0.7853981633974483 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0 0 0.12 0 0 0</pose>
|
||
|
<mass>1</mass>
|
||
|
<inertia>
|
||
|
<ixx>0.0051</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0051</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0006</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<visual name='visual_high_stiffness'>
|
||
|
<pose>0 0 -0.15 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://demo_joint_stiffness/meshes/arm.stl</uri>
|
||
|
<scale>0.001 0.001 0.001</scale>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<lighting>1</lighting>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/Orange</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name='joint_high_stiffness' type='revolute'>
|
||
|
<parent>link_base</parent>
|
||
|
<child>link_high_stiffness</child>
|
||
|
<pose>0 0 0 -0.15 0 0</pose>
|
||
|
<axis>
|
||
|
<xyz>1 0 0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>0</damping>
|
||
|
<friction>0</friction>
|
||
|
<!-- Position where the link is vertical -->
|
||
|
<spring_reference>-0.7853981633974483</spring_reference>
|
||
|
<!--
|
||
|
Spring stiffness coefficient
|
||
|
The stiffness coefficient causes a torque (force for prismatic
|
||
|
joints) to be applied based on the current joint position.
|
||
|
At the spring_reference position no torque is applied.
|
||
|
At any other position a torque is applied to the joint with a
|
||
|
direction towards the spring_reference position.
|
||
|
torque = spring_stiffness * (spring_reference - current_position)
|
||
|
-->
|
||
|
<spring_stiffness>7</spring_stiffness>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<link name='link_medium_stiffness'>
|
||
|
<gravity>0</gravity>
|
||
|
<pose>0 0 0.15 0.7853981633974483 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0 0 0.12 0 0 0</pose>
|
||
|
<mass>1</mass>
|
||
|
<inertia>
|
||
|
<ixx>0.0051</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0051</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0006</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<visual name='visual_medium_stiffness'>
|
||
|
<pose>0 0 -0.15 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://demo_joint_stiffness/meshes/arm.stl</uri>
|
||
|
<scale>0.001 0.001 0.001</scale>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<lighting>1</lighting>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/Orange</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name='joint_medium_stiffness' type='revolute'>
|
||
|
<parent>link_base</parent>
|
||
|
<child>link_medium_stiffness</child>
|
||
|
<pose>0 0 0 -0.15 0 0</pose>
|
||
|
<axis>
|
||
|
<xyz>1 0 0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>0</damping>
|
||
|
<friction>0</friction>
|
||
|
<spring_reference>-0.7853981633974483</spring_reference>
|
||
|
<spring_stiffness>0.7</spring_stiffness>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<link name='link_low_stiffness'>
|
||
|
<gravity>0</gravity>
|
||
|
<pose>-0.12 0 0.15 0.7853981633974483 0 0</pose>
|
||
|
<inertial>
|
||
|
<pose>0 0 0.12 0 0 0</pose>
|
||
|
<mass>1</mass>
|
||
|
<inertia>
|
||
|
<ixx>0.0051</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0051</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0006</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<visual name='visual_low_stiffness'>
|
||
|
<pose>0 0 -0.15 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://demo_joint_stiffness/meshes/arm.stl</uri>
|
||
|
<scale>0.001 0.001 0.001</scale>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<lighting>1</lighting>
|
||
|
<script>
|
||
|
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||
|
<name>Gazebo/Orange</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
<cast_shadows>1</cast_shadows>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name='joint_low_stiffness' type='revolute'>
|
||
|
<parent>link_base</parent>
|
||
|
<child>link_low_stiffness</child>
|
||
|
<pose>0 0 0 -0.15 0 0</pose>
|
||
|
<axis>
|
||
|
<xyz>1 0 0</xyz>
|
||
|
<dynamics>
|
||
|
<damping>0</damping>
|
||
|
<friction>0</friction>
|
||
|
<spring_reference>-0.7853981633974483</spring_reference>
|
||
|
<spring_stiffness>0.07</spring_stiffness>
|
||
|
</dynamics>
|
||
|
</axis>
|
||
|
</joint>
|
||
|
<allow_auto_disable>1</allow_auto_disable>
|
||
|
</model>
|
||
|
</sdf>
|