Skip to content
Snippets Groups Projects
Commit 56c6c6b2 authored by Sebastian Ebert's avatar Sebastian Ebert
Browse files

decreased joint-limits, to never let the cartesian motion planner again hit the original limits

parent 8d328de1
No related branches found
No related tags found
No related merge requests found
...@@ -66,7 +66,7 @@ ...@@ -66,7 +66,7 @@
<parent link="${arm_id}_link0"/> <parent link="${arm_id}_link0"/>
<child link="${arm_id}_link1"/> <child link="${arm_id}_link1"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/> <limit effort="87" lower="-2.7973" upper="2.7973" velocity="2.1750"/>
</joint> </joint>
<link name="${arm_id}_link2"> <link name="${arm_id}_link2">
<visual> <visual>
...@@ -99,7 +99,7 @@ ...@@ -99,7 +99,7 @@
<parent link="${arm_id}_link1"/> <parent link="${arm_id}_link1"/>
<child link="${arm_id}_link2"/> <child link="${arm_id}_link2"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="87" lower="-1.7628" upper="1.7628" velocity="2.1750"/> <limit effort="87" lower="-1.6628" upper="1.6628" velocity="2.1750"/>
</joint> </joint>
<link name="${arm_id}_link3"> <link name="${arm_id}_link3">
<visual> <visual>
...@@ -132,7 +132,7 @@ ...@@ -132,7 +132,7 @@
<parent link="${arm_id}_link2"/> <parent link="${arm_id}_link2"/>
<child link="${arm_id}_link3"/> <child link="${arm_id}_link3"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/> <limit effort="87" lower="-2.6973" upper="2.6973" velocity="2.1750"/>
</joint> </joint>
<link name="${arm_id}_link4"> <link name="${arm_id}_link4">
<visual> <visual>
...@@ -165,7 +165,7 @@ ...@@ -165,7 +165,7 @@
<parent link="${arm_id}_link3"/> <parent link="${arm_id}_link3"/>
<child link="${arm_id}_link4"/> <child link="${arm_id}_link4"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750"/> <limit effort="87" lower="-2.9718" upper="0.0000" velocity="2.1750"/>
</joint> </joint>
<link name="${arm_id}_link5"> <link name="${arm_id}_link5">
<visual> <visual>
...@@ -217,7 +217,7 @@ ...@@ -217,7 +217,7 @@
<parent link="${arm_id}_link4"/> <parent link="${arm_id}_link4"/>
<child link="${arm_id}_link5"/> <child link="${arm_id}_link5"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/> <limit effort="12" lower="-2.7973" upper="2.7973" velocity="2.6100"/>
</joint> </joint>
<link name="${arm_id}_link6"> <link name="${arm_id}_link6">
<visual> <visual>
...@@ -250,7 +250,7 @@ ...@@ -250,7 +250,7 @@
<parent link="${arm_id}_link5"/> <parent link="${arm_id}_link5"/>
<child link="${arm_id}_link6"/> <child link="${arm_id}_link6"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.6100"/> <limit effort="12" lower="0.0000" upper="3.6525" velocity="2.6100"/>
</joint> </joint>
<link name="${arm_id}_link7"> <link name="${arm_id}_link7">
<visual> <visual>
...@@ -283,7 +283,7 @@ ...@@ -283,7 +283,7 @@
<parent link="${arm_id}_link6"/> <parent link="${arm_id}_link6"/>
<child link="${arm_id}_link7"/> <child link="${arm_id}_link7"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/> <limit effort="12" lower="-2.7973" upper="2.7973" velocity="2.6100"/>
</joint> </joint>
<link name="${arm_id}_link8"> <link name="${arm_id}_link8">
<collision> <collision>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment