Skip to content
Snippets Groups Projects
Commit 125b1ac4 authored by Wim Meeussen's avatar Wim Meeussen
Browse files

update joint velocity limits

parent 691c02c1
Branches
Tags
No related merge requests found
...@@ -53,7 +53,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -53,7 +53,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "shoulder_link" /> <child link = "shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" /> <axis xyz="0.0 0.0 1.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="0.1" friction="0.1"/> <dynamics damping="0.1" friction="0.1"/>
</joint> </joint>
...@@ -82,7 +82,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -82,7 +82,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "upper_arm_link" /> <child link = "upper_arm_link" />
<origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" /> <origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" /> <axis xyz="0.0 1.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="0.1" friction="0.1"/> <dynamics damping="0.1" friction="0.1"/>
</joint> </joint>
...@@ -111,7 +111,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -111,7 +111,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "forearm_link" /> <child link = "forearm_link" />
<origin xyz="0.0 ${-shoulder_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 ${-shoulder_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" /> <axis xyz="0.0 1.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="0.1" friction="0.1"/> <dynamics damping="0.1" friction="0.1"/>
</joint> </joint>
...@@ -140,7 +140,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -140,7 +140,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "wrist_1_link" /> <child link = "wrist_1_link" />
<origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" /> <origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" /> <axis xyz="0.0 1.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="0.1" friction="0.1"/> <dynamics damping="0.1" friction="0.1"/>
</joint> </joint>
...@@ -169,7 +169,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -169,7 +169,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "wrist_2_link" /> <child link = "wrist_2_link" />
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" /> <axis xyz="0.0 0.0 1.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="0.1" friction="0.1"/> <dynamics damping="0.1" friction="0.1"/>
</joint> </joint>
...@@ -198,7 +198,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -198,7 +198,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "wrist_3_link" /> <child link = "wrist_3_link" />
<origin xyz="0.0 0.0 ${wrist_3_length}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 0.0 ${wrist_3_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" /> <axis xyz="0.0 1.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="0.1" friction="0.1"/> <dynamics damping="0.1" friction="0.1"/>
</joint> </joint>
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment