97 lines
2.5 KiB
XML
97 lines
2.5 KiB
XML
<?xml version="1.0" ?>
|
|
<sdf version="1.5">
|
|
<model name="cfm_damping_implicit_spring_damper_conversion_test">
|
|
<link name="world" />
|
|
<link name="link1" />
|
|
<link name="link2" />
|
|
<joint name="jointw1" type="continuous">
|
|
<parent>link1</parent>
|
|
<child>link2</child>
|
|
<axis>
|
|
<xyz>1.0 0 0</xyz>
|
|
<use_parent_model_frame>true</use_parent_model_frame>
|
|
</axis>
|
|
</joint>
|
|
<joint name="joint12a" type="revolute">
|
|
<parent>link1</parent>
|
|
<child>link2</child>
|
|
<axis>
|
|
<xyz>1.0 0 0</xyz>
|
|
<limit>
|
|
<lower>0.000000</lower>
|
|
<upper>1.000000</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<damping>1.000000</damping>
|
|
</dynamics>
|
|
<use_parent_model_frame>true</use_parent_model_frame>
|
|
</axis>
|
|
<physics>
|
|
<ode>
|
|
<cfm_damping>0</cfm_damping>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
<joint name="joint12b" type="revolute">
|
|
<parent>link1</parent>
|
|
<child>link2</child>
|
|
<axis>
|
|
<xyz>1.0 0 0</xyz>
|
|
<limit>
|
|
<lower>0.000000</lower>
|
|
<upper>1.000000</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<damping>1.000000</damping>
|
|
</dynamics>
|
|
<use_parent_model_frame>true</use_parent_model_frame>
|
|
</axis>
|
|
<physics>
|
|
<ode>
|
|
<cfm_damping>true</cfm_damping>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
<joint name="joint12c" type="revolute">
|
|
<parent>link1</parent>
|
|
<child>link2</child>
|
|
<axis>
|
|
<xyz>1.0 0 0</xyz>
|
|
<limit>
|
|
<lower>0.000000</lower>
|
|
<upper>1.000000</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<damping>1.000000</damping>
|
|
</dynamics>
|
|
<use_parent_model_frame>true</use_parent_model_frame>
|
|
</axis>
|
|
<physics>
|
|
<ode>
|
|
<implicit_spring_damper>0</implicit_spring_damper>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
<joint name="joint12d" type="revolute">
|
|
<parent>link1</parent>
|
|
<child>link2</child>
|
|
<axis>
|
|
<xyz>1.0 0 0</xyz>
|
|
<limit>
|
|
<lower>0.000000</lower>
|
|
<upper>1.000000</upper>
|
|
</limit>
|
|
<dynamics>
|
|
<damping>1.000000</damping>
|
|
</dynamics>
|
|
<use_parent_model_frame>true</use_parent_model_frame>
|
|
</axis>
|
|
<physics>
|
|
<ode>
|
|
<implicit_spring_damper>true</implicit_spring_damper>
|
|
</ode>
|
|
</physics>
|
|
</joint>
|
|
</model>
|
|
</sdf>
|