Skip to content

Commit

Permalink
Merge pull request #5 from mmurooka/jvrc1-gripper
Browse files Browse the repository at this point in the history
[JVRC1] Widen the width of the grippers
  • Loading branch information
gergondet authored Dec 15, 2022
2 parents 507d45f + 345d158 commit 1bb4203
Show file tree
Hide file tree
Showing 8 changed files with 74 additions and 20 deletions.
2 changes: 2 additions & 0 deletions jvrc_description/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,5 @@ jvrc_description
This package contains the robot description for the JVRC-1 robot.

This robot is a virtual robot initially created for the JVRC competition. The original VRML model can be retrieved from [github](https://github.com/jvrc/model). This model was initially obtained using [simtrans](https://github.com/fkanehiro/simtrans).

The URDF model in this package corresponds to [the VRML model in mc_openrtm](https://github.com/jrl-umi3218/mc_openrtm/tree/master/projects/JVRC1/model/JVRC1). Compared to the original model, the grippers are wider so that they are more suitable for manipulation.
13 changes: 13 additions & 0 deletions jvrc_description/calib/jvrc1/calib_data.LeftFootForceSensor
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
1.4985
0.000850403
-0.000949867
0.000180785
0.0300823
6.28095e-05
-0.069893
0.000222272
-0.000349766
-3.50976e-05
0.0125975
0.00543415
-0.0225577
13 changes: 13 additions & 0 deletions jvrc_description/calib/jvrc1/calib_data.LeftHandForceSensor
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
1.70009
0.000134036
-0.000370303
0.000185951
2.31464e-05
-0.00543527
-0.111911
0.000575967
-0.000872442
0.000114687
0.00696926
0.000691477
-0.0337171
13 changes: 13 additions & 0 deletions jvrc_description/calib/jvrc1/calib_data.RightFootForceSensor
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
1.49662
0.00250952
-0.00269148
0.000313644
0.0301967
0.000200838
-0.0697468
0.00227276
-0.00161345
0.000260779
0.0365667
0.0251883
-0.0396339
13 changes: 13 additions & 0 deletions jvrc_description/calib/jvrc1/calib_data.RightHandForceSensor
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
1.70037
-0.000201104
-0.00065239
0.000240497
9.98885e-05
0.00541507
-0.111914
0.00027548
-0.000885336
-0.000117922
0.00706438
0.00461102
-0.0339486
2 changes: 1 addition & 1 deletion jvrc_description/rsdf/jvrc1/l_wrist.rsdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" ?>
<robot name="jvrc1">
<gripper_surface name="LeftGripper" link="l_wrist">
<origin rpy="3.14 0.0 0.0" xyz="0.025 0.0 -0.095" />
<origin rpy="3.14 0.0 0.0" xyz="0.0 -0.0085 -0.095" />
<motor rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0" max_torque="1000" />
<points>
<origin rpy="-1.5707964897155762 -0.0 0.0" xyz="0.0 0.02 0.0" />
Expand Down
2 changes: 1 addition & 1 deletion jvrc_description/rsdf/jvrc1/r_wrist.rsdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" ?>
<robot name="jvrc1">
<gripper_surface name="RightGripper" link="r_wrist">
<origin rpy="3.14 0.0 0.0" xyz="0.025 0.0 -0.095" />
<origin rpy="3.14 0.0 0.0" xyz="0.0 0.0085 -0.095" />
<motor rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0" max_torque="1000" />
<points>
<origin rpy="-1.5707964897155762 -0.0 0.0" xyz="0.0 0.02 0.0" />
Expand Down
36 changes: 18 additions & 18 deletions jvrc_description/urdf/jvrc1.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -917,51 +917,51 @@
<limit effort="100.0" lower="-2.61799387799" upper="2.61799387799" velocity="3.66519"/>
</joint>
<joint name="R_UTHUMB" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.0 0.023 -0.084"/>
<origin rpy="0.0 -0.0 0.0" xyz="0.0 0.033 -0.084"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="R_WRIST_Y_S"/>
<child link="R_UTHUMB_S"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.0" velocity="6.80678"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.785398163397" velocity="6.80678"/>
</joint>
<joint name="R_LTHUMB" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.0 -2.47024622979e-15 -0.045"/>
<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"/>
<mimic joint="R_UTHUMB" multiplier="2" offset="0"/>
<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.006 -0.102"/>
<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"/>
<mimic joint="R_UTHUMB" multiplier="-2" offset="0"/>
<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"/>
<mimic joint="R_UTHUMB" multiplier="-2" offset="0"/>
<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.006 -0.102"/>
<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"/>
<mimic joint="R_UTHUMB" multiplier="-2" offset="0"/>
<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"/>
<mimic joint="R_UTHUMB" multiplier="-2" offset="0"/>
<mimic joint="R_UTHUMB" multiplier="-3" offset="0"/>
</joint>
<joint name="L_SHOULDER_P" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.0 0.24 0.33"/>
Expand Down Expand Up @@ -1013,51 +1013,51 @@
<limit effort="100.0" lower="-2.61799387799" upper="2.61799387799" velocity="3.66519"/>
</joint>
<joint name="L_UTHUMB" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.0 -0.023 -0.084"/>
<origin rpy="0.0 -0.0 0.0" xyz="0.0 -0.033 -0.084"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="L_WRIST_Y_S"/>
<child link="L_UTHUMB_S"/>
<limit effort="100.0" lower="-0.0" upper="0.785398163397" velocity="6.80678"/>
<limit effort="100.0" lower="-0.785398163397" upper="0.785398163397" velocity="6.80678"/>
</joint>
<joint name="L_LTHUMB" type="revolute">
<origin rpy="0.0 -0.0 0.0" xyz="0.0 2.16493489802e-15 -0.045"/>
<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"/>
<mimic joint="L_UTHUMB" multiplier="2" offset="0"/>
<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.006 -0.102"/>
<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"/>
<mimic joint="L_UTHUMB" multiplier="-2" offset="0"/>
<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"/>
<mimic joint="L_UTHUMB" multiplier="-2" offset="0"/>
<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.006 -0.102"/>
<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"/>
<mimic joint="L_UTHUMB" multiplier="-2" offset="0"/>
<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"/>
<mimic joint="L_UTHUMB" multiplier="-2" offset="0"/>
<mimic joint="L_UTHUMB" multiplier="-3" offset="0"/>
</joint>
<link name="gsensor">
</link>
Expand Down

0 comments on commit 1bb4203

Please sign in to comment.