Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Gepetto
example-robot-data
Commits
c69dd9f4
Commit
c69dd9f4
authored
Oct 28, 2019
by
Carlos Mastalli
Browse files
[anymal] Added the ANYmal with kinova arm
parent
0e45e3b4
Changes
5
Expand all
Hide whitespace changes
Inline
Side-by-side
anymal_b_simple_description/robots/anymal-kinova.urdf
0 → 100644
View file @
c69dd9f4
This diff is collapsed.
Click to expand it.
anymal_b_simple_description/srdf/anymal-kinova.srdf
0 → 100644
View file @
c69dd9f4
<?xml version="1.0" ?>
<robot
name=
"anymal"
>
<group
name=
"lf_leg"
>
<joint
name=
"LF_HAA"
/>
<joint
name=
"LF_HFE"
/>
<joint
name=
"LF_KFE"
/>
<chain
base_link=
"base"
tip_link=
"LF_FOOT"
/>
</group>
<group
name=
"lh_leg"
>
<joint
name=
"LH_HAA"
/>
<joint
name=
"LH_HFE"
/>
<joint
name=
"LH_KFE"
/>
<chain
base_link=
"base"
tip_link=
"LH_FOOT"
/>
</group>
<group
name=
"rf_leg"
>
<joint
name=
"RF_HAA"
/>
<joint
name=
"RF_HFE"
/>
<joint
name=
"RF_KFE"
/>
<chain
base_link=
"base"
tip_link=
"RF_FOOT"
/>
</group>
<group
name=
"rh_leg"
>
<joint
name=
"RH_HAA"
/>
<joint
name=
"RH_HFE"
/>
<joint
name=
"RH_KFE"
/>
<chain
base_link=
"base"
tip_link=
"RH_FOOT"
/>
</group>
<group
name=
"all_legs"
>
<group
name=
"lf"
/>
<group
name=
"rf"
/>
<group
name=
"lh"
/>
<group
name=
"rh"
/>
</group>
<group
name=
"r_legs"
>
<group
name=
"rf"
/>
<group
name=
"rh"
/>
</group>
<group
name=
"l_legs"
>
<group
name=
"lf"
/>
<group
name=
"lh"
/>
</group>
<group
name=
"f_legs"
>
<group
name=
"lf"
/>
<group
name=
"rf"
/>
</group>
<group
name=
"h_legs"
>
<group
name=
"lh"
/>
<group
name=
"rh"
/>
</group>
<group
name=
"ld_legs"
>
<group
name=
"lf"
/>
<group
name=
"rh"
/>
</group>
<group
name=
"rd_legs"
>
<group
name=
"rf"
/>
<group
name=
"lh"
/>
</group>
<end_effector
name=
"lf_foot"
parent_link=
"LF_FOOT"
group=
"lf_leg"
/>
<end_effector
name=
"rf_foot"
parent_link=
"RF_FOOT"
group=
"rf_leg"
/>
<end_effector
name=
"lh_foot"
parent_link=
"LH_FOOT"
group=
"lh_leg"
/>
<end_effector
name=
"rh_foot"
parent_link=
"RH_FOOT"
group=
"rh_leg"
/>
<group_state
name=
"half_sitting"
group=
"all_legs"
>
<joint
name=
"root_joint"
value=
"0. 0. 0.4792 0. 0. 0. 1."
/>
<joint
name=
"LF_HAA"
value=
"-0.1"
/>
<joint
name=
"LF_HFE"
value=
"0.7"
/>
<joint
name=
"LF_KFE"
value=
"-1."
/>
<joint
name=
"RF_HAA"
value=
"0.1"
/>
<joint
name=
"RF_HFE"
value=
"0.7"
/>
<joint
name=
"RF_KFE"
value=
"-1."
/>
<joint
name=
"LH_HAA"
value=
"-0.1"
/>
<joint
name=
"LH_HFE"
value=
"-0.7"
/>
<joint
name=
"LH_KFE"
value=
"1."
/>
<joint
name=
"RH_HAA"
value=
"0.1"
/>
<joint
name=
"RH_HFE"
value=
"-0.7"
/>
<joint
name=
"RH_KFE"
value=
"1."
/>
<joint
name=
"j2s6s200_joint_1"
value=
"1.5707"
/>
<joint
name=
"j2s6s200_joint_2"
value=
"2.618"
/>
<joint
name=
"j2s6s200_joint_3"
value=
"-1.5707"
/>
<joint
name=
"j2s6s200_joint_4"
value=
"3.1415"
/>
<joint
name=
"j2s6s200_joint_5"
value=
"2.618"
/>
<joint
name=
"j2s6s200_joint_6"
value=
"0."
/>
</group_state>
<disable_collisions
link1=
"LF_HIP"
link2=
"LF_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LF_SHANK"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LF_FOOT"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RF_HIP"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RF_THIGH"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RF_SHANK"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RF_FOOT"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LH_HIP"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LH_THIGH"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LH_SHANK"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LH_FOOT"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RH_HIP"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RH_THIGH"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RH_SHANK"
reason=
"Never"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"RH_FOOT"
reason=
"Never"
/>
<disable_collisions
link1=
"base"
link2=
"LF_HIP"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"LH_HIP"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"RF_HIP"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"RH_HIP"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LF_HIP"
link2=
"LF_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LH_HIP"
link2=
"LH_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RF_HIP"
link2=
"RF_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RH_HIP"
link2=
"RH_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LF_THIGH"
link2=
"LF_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LH_THIGH"
link2=
"LH_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RF_THIGH"
link2=
"RF_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RH_THIGH"
link2=
"RH_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LF_SHANK"
link2=
"LF_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LH_SHANK"
link2=
"LH_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RF_SHANK"
link2=
"RF_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RH_SHANK"
link2=
"RH_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LF_ADAPTER"
link2=
"LF_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LH_ADAPTER"
link2=
"LH_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RF_ADAPTER"
link2=
"RF_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RH_ADAPTER"
link2=
"RH_FOOT"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LF_ADAPTER"
link2=
"LF_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"LH_ADAPTER"
link2=
"LH_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RF_ADAPTER"
link2=
"RF_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"RH_ADAPTER"
link2=
"RH_SHANK"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"imu_link"
reason=
"Adjacent"
/>
<!-- Need to check these 4 ? there may be auto-collisions ... -->
<disable_collisions
link1=
"base"
link2=
"LF_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"LH_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"RF_THIGH"
reason=
"Adjacent"
/>
<disable_collisions
link1=
"base"
link2=
"RH_THIGH"
reason=
"Adjacent"
/>
</robot>
kinova_description/robots/kinova.urdf
View file @
c69dd9f4
...
...
@@ -4,7 +4,7 @@
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!-- This file contains the description of the ANYmal Bedi robot. -->
<robot
name=
"
anymal"
<robot
name=
"
kinova"
xmlns:xacro=
"http://www.ros.org/wiki/xacro"
>
<material
name=
"black"
>
<color
rgba=
"0.0 0.0 0.0 1.0"
/>
...
...
python/example_robot_data/__main__.py
View file @
c69dd9f4
...
...
@@ -3,7 +3,7 @@ from argparse import ArgumentParser
from
.
import
robots_loader
ROBOTS
=
[
'anymal'
,
'hyq'
,
'solo'
,
'solo12'
,
'talos'
,
'talos_arm'
,
'talos_legs'
,
'kinova'
,
'tiago'
,
'tiago_no_hand'
,
'icub'
,
'ur5'
'anymal'
,
'anymal_kinova'
,
'hyq'
,
'solo'
,
'solo12'
,
'talos'
,
'talos_arm'
,
'talos_legs'
,
'kinova'
,
'tiago'
,
'tiago_no_hand'
,
'icub'
,
'ur5'
]
parser
=
ArgumentParser
()
...
...
@@ -16,6 +16,11 @@ if args.robot == 'anymal':
anymal
.
initViewer
(
loadModel
=
True
)
anymal
.
display
(
anymal
.
q0
)
elif
args
.
robot
==
'anymal_kinova'
:
anymal
=
robots_loader
.
loadANYmal
(
withArm
=
'kinova'
)
anymal
.
initViewer
(
loadModel
=
True
)
anymal
.
display
(
anymal
.
q0
)
elif
args
.
robot
==
'hyq'
:
hyq
=
robots_loader
.
loadHyQ
()
hyq
.
initViewer
(
loadModel
=
True
)
...
...
python/example_robot_data/robots_loader.py
View file @
c69dd9f4
...
...
@@ -44,10 +44,14 @@ def addFreeFlyerJointLimits(robot):
rmodel
.
lowerPositionLimit
=
lb
def
loadANYmal
():
URDF_FILENAME
=
"anymal.urdf"
def
loadANYmal
(
withArm
=
None
):
if
withArm
is
None
:
URDF_FILENAME
=
"anymal.urdf"
SRDF_FILENAME
=
"anymal.srdf"
elif
withArm
is
"kinova"
:
URDF_FILENAME
=
"anymal-kinova.urdf"
SRDF_FILENAME
=
"anymal-kinova.srdf"
URDF_SUBPATH
=
"/anymal_b_simple_description/robots/"
+
URDF_FILENAME
SRDF_FILENAME
=
"anymal.srdf"
SRDF_SUBPATH
=
"/anymal_b_simple_description/srdf/"
+
SRDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment