Skip to content

Commit

Permalink
effort limits
Browse files Browse the repository at this point in the history
  • Loading branch information
Aron Svastits committed Sep 4, 2023
1 parent 96a2f46 commit af0f9a3
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 12 deletions.
12 changes: 6 additions & 6 deletions kuka_quantec_support/urdf/kr210_r2700-2_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -154,42 +154,42 @@
<joint name="${prefix}joint_a1" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_1"/>
<limit effort="0" lower="-3.2288591161895095E0" upper="3.2288591161895095E0" velocity="${radians(120)}"/>
<limit effort="7290" lower="-3.2288591161895095E0" upper="3.2288591161895095E0" velocity="${radians(120)}"/>
<origin rpy="-3.141592653589793 0.0 -0.0" xyz="0.0 0.0 0.0"/>
<parent link="${prefix}base_link_inertia"/>
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_2"/>
<limit effort="0" lower="-2.443460952792061E0" upper="-8.726646259971647E-2" velocity="${radians(115)}"/>
<limit effort="8910" lower="-2.443460952792061E0" upper="-8.726646259971647E-2" velocity="${radians(115)}"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.33 0.0 -0.645"/>
<parent link="${prefix}link_1"/>
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_3"/>
<limit effort="0" lower="-2.0943951023931953E0" upper="2.9321531433504737E0" velocity="${radians(112)}"/>
<limit effort="6988.84717" lower="-2.0943951023931953E0" upper="2.9321531433504737E0" velocity="${radians(112)}"/>
<origin rpy="0.0 0.0 -1.5707963267948963" xyz="1.15 0.0 0.0"/>
<parent link="${prefix}link_2"/>
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_4"/>
<limit effort="0" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(179)}"/>
<limit effort="2274.29199" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(179)}"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.115 0.0 0.0"/>
<parent link="${prefix}link_3"/>
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_5"/>
<limit effort="0" lower="-2.181661564992912E0" upper="2.181661564992912E0" velocity="${radians(172)}"/>
<limit effort="1398.30298" lower="-2.181661564992912E0" upper="2.181661564992912E0" velocity="${radians(172)}"/>
<origin rpy="-1.5707963267948963 0.0 -0.0" xyz="0.0 0.0 -1.22"/>
<parent link="${prefix}link_4"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_6"/>
<limit effort="0" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(220)}"/>
<limit effort="781.554626" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(220)}"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.0 0.0 0.0"/>
<parent link="${prefix}link_5"/>
</joint>
Expand Down
12 changes: 6 additions & 6 deletions kuka_quantec_support/urdf/kr210_r3100-2_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -155,42 +155,42 @@
<joint name="${prefix}joint_a1" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_1"/>
<limit effort="0" lower="-3.2288591161895095E0" upper="3.2288591161895095E0" velocity="${radians(105)}"/>
<limit effort="7290" lower="-3.2288591161895095E0" upper="3.2288591161895095E0" velocity="${radians(105)}"/>
<origin rpy="-3.141592653589793 0.0 -0.0" xyz="0.0 0.0 0.0"/>
<parent link="${prefix}base_link_inertia"/>
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_2"/>
<limit effort="0" lower="-2.443460952792061E0" upper="-8.726646259971647E-2" velocity="${radians(94)}"/>
<limit effort="8910" lower="-2.443460952792061E0" upper="-8.726646259971647E-2" velocity="${radians(94)}"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.33 0.0 -0.645"/>
<parent link="${prefix}link_1"/>
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_3"/>
<limit effort="0" lower="-2.0943951023931953E0" upper="2.9321531433504737E0" velocity="${radians(100)}"/>
<limit effort="7251.2876" lower="-2.0943951023931953E0" upper="2.9321531433504737E0" velocity="${radians(100)}"/>
<origin rpy="0.0 0.0 -1.5707963267948963" xyz="1.35 0.0 0.0"/>
<parent link="${prefix}link_2"/>
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_4"/>
<limit effort="0" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(136)}"/>
<limit effort="2356.12598" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(136)}"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.115 0.0 0.0"/>
<parent link="${prefix}link_3"/>
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_5"/>
<limit effort="0" lower="-2.138028333693054E0" upper="2.138028333693054E0" velocity="${radians(129)}"/>
<limit effort="2358.44531" lower="-2.138028333693054E0" upper="2.138028333693054E0" velocity="${radians(129)}"/>
<origin rpy="-1.5707963267948963 0.0 -0.0" xyz="0.0 0.0 -1.42"/>
<parent link="${prefix}link_4"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_6"/>
<limit effort="0" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(206)}"/>
<limit effort="1508.75476" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="${radians(206)}"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.0 0.0 0.0"/>
<parent link="${prefix}link_5"/>
</joint>
Expand Down

0 comments on commit af0f9a3

Please sign in to comment.