Skip to content

Commit

Permalink
Merge pull request #7 from gergondet/topic/UpdateGripperLimits
Browse files Browse the repository at this point in the history
  • Loading branch information
gergondet authored Jan 4, 2023
2 parents b66f953 + dcfbe3a commit c5087e1
Showing 1 changed file with 10 additions and 10 deletions.
20 changes: 10 additions & 10 deletions jvrc_description/urdf/jvrc1.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -928,39 +928,39 @@
<axis xyz="1.0 0.0 0.0"/>
<parent link="R_UTHUMB_S"/>
<child link="R_LTHUMB_S"/>
<limit effort="100.0" lower="-1.57079632679" upper="0.0" velocity="13.6135"/>
<limit effort="300.0" lower="-2.356194490191" upper="2.356194490191" velocity="20.42034"/>
<mimic joint="R_UTHUMB" multiplier="3" offset="0"/>
</joint>
<joint name="R_UINDEX" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.025 -0.016 -0.084"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="R_WRIST_Y_S"/>
<child link="R_UINDEX_S"/>
<limit effort="100.0" lower="0.0" upper="1.57079632679" velocity="9.42477"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.785398163397" velocity="6.80678"/>
<mimic joint="R_UTHUMB" multiplier="-1" offset="0"/>
</joint>
<joint name="R_LINDEX" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="3.46944695195e-17 -2.77555756156e-17 -0.045"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="R_UINDEX_S"/>
<child link="R_LINDEX_S"/>
<limit effort="100.0" lower="0.0" upper="1.57079632679" velocity="5.75958"/>
<limit effort="300.0" lower="-2.356194490191" upper="2.356194490191" velocity="20.42034"/>
<mimic joint="R_UTHUMB" multiplier="-3" offset="0"/>
</joint>
<joint name="R_ULITTLE" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="-0.025 -0.016 -0.084"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="R_WRIST_Y_S"/>
<child link="R_ULITTLE_S"/>
<limit effort="100.0" lower="0.0" upper="1.57079632679" velocity="9.42477"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.785398163397" velocity="6.80678"/>
<mimic joint="R_UTHUMB" multiplier="-1" offset="0"/>
</joint>
<joint name="R_LLITTLE" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="-3.46944695195e-17 -1.38777878078e-16 -0.045"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="R_ULITTLE_S"/>
<child link="R_LLITTLE_S"/>
<limit effort="100.0" lower="0.0" upper="1.57079632679" velocity="5.75958"/>
<limit effort="300.0" lower="-2.356194490191" upper="2.356194490191" velocity="20.42034"/>
<mimic joint="R_UTHUMB" multiplier="-3" offset="0"/>
</joint>
<joint name="L_SHOULDER_P" type="revolute">
Expand Down Expand Up @@ -1024,39 +1024,39 @@
<axis xyz="1.0 0.0 0.0"/>
<parent link="L_UTHUMB_S"/>
<child link="L_LTHUMB_S"/>
<limit effort="100.0" lower="-0.0" upper="1.57079632679" velocity="13.6135"/>
<limit effort="300.0" lower="-2.356194490191" upper="2.356194490191" velocity="20.42034"/>
<mimic joint="L_UTHUMB" multiplier="3" offset="0"/>
</joint>
<joint name="L_UINDEX" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.025 0.016 -0.084"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="L_WRIST_Y_S"/>
<child link="L_UINDEX_S"/>
<limit effort="100.0" lower="-1.57079632679" upper="0.0" velocity="9.42477"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.785398163397" velocity="6.80678"/>
<mimic joint="L_UTHUMB" multiplier="-1" offset="0"/>
</joint>
<joint name="L_LINDEX" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="3.46944695195e-17 1.38777878078e-16 -0.045"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="L_UINDEX_S"/>
<child link="L_LINDEX_S"/>
<limit effort="100.0" lower="-1.57079632679" upper="0.0" velocity="5.75958"/>
<limit effort="300.0" lower="-2.356194490191" upper="2.356194490191" velocity="20.42034"/>
<mimic joint="L_UTHUMB" multiplier="-3" offset="0"/>
</joint>
<joint name="L_ULITTLE" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="-0.025 0.016 -0.084"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="L_WRIST_Y_S"/>
<child link="L_ULITTLE_S"/>
<limit effort="100.0" lower="-1.57079632679" upper="0.0" velocity="9.42477"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.785398163397" velocity="6.80678"/>
<mimic joint="L_UTHUMB" multiplier="-1" offset="0"/>
</joint>
<joint name="L_LLITTLE" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="-3.46944695195e-17 2.77555756156e-17 -0.045"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="L_ULITTLE_S"/>
<child link="L_LLITTLE_S"/>
<limit effort="100.0" lower="-1.57079632679" upper="0.0" velocity="5.75958"/>
<limit effort="300.0" lower="-2.356194490191" upper="2.356194490191" velocity="20.42034"/>
<mimic joint="L_UTHUMB" multiplier="-3" offset="0"/>
</joint>
<link name="gsensor">
Expand Down

0 comments on commit c5087e1

Please sign in to comment.