Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
E
example-robot-data
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Gepetto
example-robot-data
Commits
e2d81810
Commit
e2d81810
authored
2 years ago
by
Louis Montaut
Browse files
Options
Downloads
Patches
Plain Diff
core: adding allegro left hand
parent
0861ddf1
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
python/example_robot_data/robots_loader.py
+7
-0
7 additions, 0 deletions
python/example_robot_data/robots_loader.py
robots/allegro_hand_description/urdf/allegro_left_hand.urdf
+509
-0
509 additions, 0 deletions
robots/allegro_hand_description/urdf/allegro_left_hand.urdf
with
516 additions
and
0 deletions
python/example_robot_data/robots_loader.py
+
7
−
0
View file @
e2d81810
...
...
@@ -393,6 +393,12 @@ class AllegroRightHandLoader(RobotLoader):
urdf_subpath
=
"
urdf
"
class
AllegroLeftHandLoader
(
RobotLoader
):
path
=
"
allegro_hand_description
"
urdf_filename
=
"
allegro_left_hand.urdf
"
urdf_subpath
=
"
urdf
"
class
UR3Loader
(
RobotLoader
):
path
=
"
ur_description
"
urdf_filename
=
"
ur3_robot.urdf
"
...
...
@@ -496,6 +502,7 @@ ROBOTS = {
"
laikago
"
:
LaikagoLoader
,
"
panda
"
:
PandaLoader
,
"
allegro_right_hand
"
:
AllegroRightHandLoader
,
"
allegro_left_hand
"
:
AllegroLeftHandLoader
,
"
romeo
"
:
RomeoLoader
,
"
simple_humanoid
"
:
SimpleHumanoidLoader
,
"
simple_humanoid_classical
"
:
SimpleHumanoidClassicalLoader
,
...
...
This diff is collapsed.
Click to expand it.
robots/allegro_hand_description/urdf/allegro_left_hand.urdf
0 → 100644
+
509
−
0
View file @
e2d81810
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from allegro_hand_description_left.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot
name=
"allegro_hand_left"
xmlns:xacro=
"http://www.ros.org/wiki/xacro"
>
<!--
rosrun xacro xacro.py allegro_hand_description_right.urdf.xacro > allegro_hand_description_right.urdf
roslaunch launchers/fuerte/allegro_hand_jgui_right_virtual.launch
-->
<!-- ======================== BASE PARAMS ========================= -->
<!-- ======================== FINGER PARAMS ======================== -->
<!-- full height from joint to tip. when used,
the radius of the finger tip sphere will be subtracted
and one fixed link will be added for the tip. -->
<!--0.0435, 0.044981-->
<!--0.002298-->
<!--0.002298-->
<!-- ========================= THUMB PARAMS ========================= -->
<!-- ========================= LIMITS ========================= -->
<!-- ============================================================================= -->
<!-- ============================================================================= -->
<!-- ============================================================================= -->
<!-- BASE -->
<link
name=
"base_link"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/base_link_left.STL"
/>
</geometry>
<!-- LEFT -->
<origin
rpy=
"-1.5707963259 0 0"
xyz=
"0 0 0 "
/>
<!-- RIGHT -->
<!--<origin rpy="0 0 0" xyz="0 0 0 "/>-->
<material
name=
"black"
>
<color
rgba=
"0.2 0.2 0.2 1"
/>
</material>
</visual>
<collision>
<origin
rpy=
"0 0 0"
xyz=
"-0.009300 0 -0.0475"
/>
<geometry>
<box
size=
"0.0408 0.1130 0.095"
/>
</geometry>
</collision>
</link>
<!-- ============================================================================= -->
<!-- FINGERS -->
<!-- RIGHT HAND due to which finger is number 0 -->
<!-- for LEFT HAND switch the sign of the **offset_origin_y** and **finger_angle_r** parameters-->
<link
name=
"link_8.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_0.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0164"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0082"
/>
</collision>
</link>
<joint
name=
"joint_8.0"
type=
"revolute"
>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"0"
lower=
"-0.47"
upper=
"0.47"
velocity=
"0"
/>
<parent
link=
"base_link"
/>
<child
link=
"link_8.0"
/>
<origin
rpy=
"-0.08726646255 0 0"
xyz=
"0 0.0435 -0.001542"
/>
</joint>
<link
name=
"link_9.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_1.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.054"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.027"
/>
</collision>
</link>
<joint
name=
"joint_9.0"
type=
"revolute"
>
<limit
effort=
"0"
lower=
"-0.196"
upper=
"1.61"
velocity=
"0"
/>
<axis
xyz=
"0 1 0"
/>
<parent
link=
"link_8.0"
/>
<child
link=
"link_9.0"
/>
<origin
xyz=
"0 0 0.0164"
/>
</joint>
<link
name=
"link_10.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_2.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0384"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0192"
/>
</collision>
</link>
<joint
name=
"joint_10.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.174"
upper=
"1.709"
velocity=
"0"
/>
<parent
link=
"link_9.0"
/>
<child
link=
"link_10.0"
/>
<origin
xyz=
"0 0 0.054"
/>
</joint>
<link
name=
"link_11.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_3.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0267"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.01335"
/>
</collision>
</link>
<joint
name=
"joint_11.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.227"
upper=
"1.618"
velocity=
"0"
/>
<parent
link=
"link_10.0"
/>
<child
link=
"link_11.0"
/>
<origin
xyz=
"0 0 0.0384"
/>
</joint>
<link
name=
"link_11.0_tip"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_3.0_tip.STL"
/>
</geometry>
<material
name=
"white"
>
<color
rgba=
".9 .9 .9 1"
/>
</material>
</visual>
<collision>
<geometry>
<sphere
radius=
"0.012"
/>
</geometry>
</collision>
</link>
<joint
name=
"joint_11.0_tip"
type=
"fixed"
>
<parent
link=
"link_11.0"
/>
<child
link=
"link_11.0_tip"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0267"
/>
</joint>
<link
name=
"link_4.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_0.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0164"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0082"
/>
</collision>
</link>
<joint
name=
"joint_4.0"
type=
"revolute"
>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"0"
lower=
"-0.47"
upper=
"0.47"
velocity=
"0"
/>
<parent
link=
"base_link"
/>
<child
link=
"link_4.0"
/>
<origin
rpy=
"0.0 0 0"
xyz=
"0 0 0.0007"
/>
</joint>
<link
name=
"link_5.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_1.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.054"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.027"
/>
</collision>
</link>
<joint
name=
"joint_5.0"
type=
"revolute"
>
<limit
effort=
"0"
lower=
"-0.196"
upper=
"1.61"
velocity=
"0"
/>
<axis
xyz=
"0 1 0"
/>
<parent
link=
"link_4.0"
/>
<child
link=
"link_5.0"
/>
<origin
xyz=
"0 0 0.0164"
/>
</joint>
<link
name=
"link_6.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_2.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0384"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0192"
/>
</collision>
</link>
<joint
name=
"joint_6.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.174"
upper=
"1.709"
velocity=
"0"
/>
<parent
link=
"link_5.0"
/>
<child
link=
"link_6.0"
/>
<origin
xyz=
"0 0 0.054"
/>
</joint>
<link
name=
"link_7.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_3.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0267"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.01335"
/>
</collision>
</link>
<joint
name=
"joint_7.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.227"
upper=
"1.618"
velocity=
"0"
/>
<parent
link=
"link_6.0"
/>
<child
link=
"link_7.0"
/>
<origin
xyz=
"0 0 0.0384"
/>
</joint>
<link
name=
"link_7.0_tip"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_3.0_tip.STL"
/>
</geometry>
<material
name=
"white"
>
<color
rgba=
".9 .9 .9 1"
/>
</material>
</visual>
<collision>
<geometry>
<sphere
radius=
"0.012"
/>
</geometry>
</collision>
</link>
<joint
name=
"joint_7.0_tip"
type=
"fixed"
>
<parent
link=
"link_7.0"
/>
<child
link=
"link_7.0_tip"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0267"
/>
</joint>
<link
name=
"link_0.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_0.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0164"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0082"
/>
</collision>
</link>
<joint
name=
"joint_0.0"
type=
"revolute"
>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"0"
lower=
"-0.47"
upper=
"0.47"
velocity=
"0"
/>
<parent
link=
"base_link"
/>
<child
link=
"link_0.0"
/>
<origin
rpy=
"0.08726646255 0 0"
xyz=
"0 -0.0435 -0.001542"
/>
</joint>
<link
name=
"link_1.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_1.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.054"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.027"
/>
</collision>
</link>
<joint
name=
"joint_1.0"
type=
"revolute"
>
<limit
effort=
"0"
lower=
"-0.196"
upper=
"1.61"
velocity=
"0"
/>
<axis
xyz=
"0 1 0"
/>
<parent
link=
"link_0.0"
/>
<child
link=
"link_1.0"
/>
<origin
xyz=
"0 0 0.0164"
/>
</joint>
<link
name=
"link_2.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_2.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0384"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0192"
/>
</collision>
</link>
<joint
name=
"joint_2.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.174"
upper=
"1.709"
velocity=
"0"
/>
<parent
link=
"link_1.0"
/>
<child
link=
"link_2.0"
/>
<origin
xyz=
"0 0 0.054"
/>
</joint>
<link
name=
"link_3.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_3.0.STL"
/>
</geometry>
<material
name=
"black"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0267"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.01335"
/>
</collision>
</link>
<joint
name=
"joint_3.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.227"
upper=
"1.618"
velocity=
"0"
/>
<parent
link=
"link_2.0"
/>
<child
link=
"link_3.0"
/>
<origin
xyz=
"0 0 0.0384"
/>
</joint>
<link
name=
"link_3.0_tip"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_3.0_tip.STL"
/>
</geometry>
<material
name=
"white"
>
<color
rgba=
".9 .9 .9 1"
/>
</material>
</visual>
<collision>
<geometry>
<sphere
radius=
"0.012"
/>
</geometry>
</collision>
</link>
<joint
name=
"joint_3.0_tip"
type=
"fixed"
>
<parent
link=
"link_3.0"
/>
<child
link=
"link_3.0_tip"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0267"
/>
</joint>
<!-- THUMB -->
<!--
<xacro:thumb_right
finger_num= "3"
offset_origin_x= "-0.0182"
offset_origin_y= "0.019333"
offset_origin_z= "-0.045987"
finger_angle_r= "0"
finger_angle_p= "-${95*DEG2RAD}"
finger_angle_y= "-${90*DEG2RAD}"
/>
-->
<!--
finger_angle_r= "${90*DEG2RAD}"
finger_angle_p= "-${100*DEG2RAD}"
finger_angle_y= "${0*DEG2RAD}"
-->
<link
name=
"link_12.0"
>
<visual>
<geometry>
<!-- RIGHT -->
<!-- <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_12.0_right.STL" /> -->
<!-- LEFT -->
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_12.0_left.STL"
/>
</geometry>
<material
name=
"black"
>
<color
rgba=
".2 .2 .2 1"
/>
</material>
<origin
rpy=
"3.1415926518 0 0"
xyz=
"0 0 0"
/>
</visual>
<collision>
<geometry>
<box
size=
"0.0358 0.034 0.0455"
/>
</geometry>
<!-- RIGHT -->
<!-- <origin rpy="0 0 0" xyz="${-0.0358/2+0.0} ${.018/2} ${.029/2}"/> -->
<!-- LEFT -->
<origin
rpy=
"0 0 0"
xyz=
"-0.0179 -0.009 0.0145"
/>
</collision>
</link>
<joint
name=
"joint_12.0"
type=
"revolute"
>
<axis
xyz=
"+1 0 0"
/>
<limit
effort=
"0"
lower=
"0.263"
upper=
"1.396"
velocity=
"0"
/>
<parent
link=
"base_link"
/>
<child
link=
"link_12.0"
/>
<origin
rpy=
"0 -1.65806278845 1.5707963259"
xyz=
"-0.0182 -0.019333 -0.045987"
/>
</joint>
<link
name=
"link_13.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_13.0.STL"
/>
</geometry>
<material
name=
"black"
>
<color
rgba=
".2 .2 .2 1"
/>
</material>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0177"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.00885"
/>
</collision>
</link>
<joint
name=
"joint_13.0"
type=
"revolute"
>
<axis
xyz=
"0 0 -1"
/>
<limit
effort=
"0"
lower=
"-0.105"
upper=
"1.163"
velocity=
"0"
/>
<parent
link=
"link_12.0"
/>
<child
link=
"link_13.0"
/>
<!-- RIGHT -->
<!-- <origin xyz="-0.027 0.005 0.0399"/> -->
<!-- LEFT -->
<origin
xyz=
"-0.027 -0.005 0.0399"
/>
</joint>
<link
name=
"link_14.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_14.0.STL"
/>
</geometry>
<material
name=
"black"
>
</material>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0514"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0257"
/>
</collision>
</link>
<joint
name=
"joint_14.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.189"
upper=
"1.644"
velocity=
"0"
/>
<parent
link=
"link_13.0"
/>
<child
link=
"link_14.0"
/>
<origin
xyz=
"0 0 0.0177"
/>
</joint>
<link
name=
"link_15.0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_15.0.STL"
/>
</geometry>
<material
name=
"black"
>
</material>
</visual>
<collision>
<geometry>
<box
size=
"0.0196 0.0275 0.0423"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.02115"
/>
</collision>
</link>
<joint
name=
"joint_15.0"
type=
"revolute"
>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"0"
lower=
"-0.162"
upper=
"1.719"
velocity=
"0"
/>
<parent
link=
"link_14.0"
/>
<child
link=
"link_15.0"
/>
<origin
xyz=
"0 0 0.0514"
/>
</joint>
<link
name=
"link_15.0_tip"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/allegro_hand_description/meshes/link_15.0_tip.STL"
/>
</geometry>
<material
name=
"white"
>
<color
rgba=
".9 .9 .9 1"
/>
</material>
</visual>
<collision>
<geometry>
<sphere
radius=
"0.012"
/>
</geometry>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
</collision>
</link>
<joint
name=
"joint_15.0_tip"
type=
"fixed"
>
<parent
link=
"link_15.0"
/>
<child
link=
"link_15.0_tip"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0423"
/>
<!--0.0267000000000005-->
</joint>
<!-- ============================================================================= -->
<!-- ============================================================================= -->
<!-- ============================================================================= -->
<!-- THUMB MACRO -->
<!-- END THUMB MACRO -->
<!-- THREE FINGER MACRO -->
<!-- [[END]] THREE FINGER MACRO -->
</robot>
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment