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
be1a995b
Commit
be1a995b
authored
Apr 16, 2019
by
Carlos Mastalli
Browse files
[format] Fixed format issues
parent
4d531528
Changes
3
Hide whitespace changes
Inline
Side-by-side
python/display.py
View file @
be1a995b
import
sys
sys
.
path
.
append
(
'/opt/openrobots/share/example-robot-data/unittest/'
)
from
unittest_utils
import
loadHyQ
,
loadTalos
,
loadTalosArm
,
loadTiago
,
loadTiagoNoHand
,
loadICub
from
unittest_utils
import
loadHyQ
,
loadICub
,
loadTalos
,
loadTalosArm
,
loadTiago
,
loadTiagoNoHand
sys
.
path
.
append
(
'/opt/openrobots/share/example-robot-data/unittest/'
)
DISPLAY_HYQ
=
'hyq'
in
sys
.
argv
DISPLAY_TALOS
=
'talos'
in
sys
.
argv
...
...
@@ -39,4 +40,3 @@ if DISPLAY_ICUB:
icub
=
loadICub
()
icub
.
initDisplay
(
loadModel
=
True
)
icub
.
display
(
icub
.
q0
)
unittest/test_load.py
View file @
be1a995b
...
...
@@ -2,7 +2,7 @@
import
unittest
from
unittest_utils
import
loadHyQ
,
loadTalos
,
loadTalosArm
,
loadTiago
,
loadTiagoNoHand
,
loadICub
from
unittest_utils
import
loadHyQ
,
loadICub
,
loadTalos
,
loadTalosArm
,
loadTiago
,
loadTiagoNoHand
class
RobotTestCase
(
unittest
.
TestCase
):
...
...
@@ -57,10 +57,12 @@ class TiagoNoHandTest(RobotTestCase):
RobotTestCase
.
NQ
=
14
RobotTestCase
.
NV
=
12
class
ICubTest
(
RobotTestCase
):
RobotTestCase
.
ROBOT
=
loadICub
()
RobotTestCase
.
NQ
=
39
RobotTestCase
.
NV
=
38
if
__name__
==
'__main__'
:
unittest
.
main
()
unittest/unittest_utils.py
View file @
be1a995b
from
os.path
import
exists
,
join
import
numpy
as
np
import
pinocchio
from
pinocchio.robot_wrapper
import
RobotWrapper
...
...
@@ -28,6 +27,7 @@ def readParamsFromSrdf(robot, SRDF_PATH, verbose):
except
:
print
"loadReferenceConfigurations did not work. Please check your
\
Pinocchio Version"
try
:
pinocchio
.
getNeutralConfiguration
(
rmodel
,
SRDF_PATH
,
verbose
)
robot
.
q0
.
flat
[:]
=
rmodel
.
neutralConfiguration
.
copy
()
...
...
@@ -43,10 +43,10 @@ def loadTalosArm():
SRDF_SUBPATH
=
"/talos_data/srdf/"
+
SRDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
return
robot
...
...
@@ -57,11 +57,10 @@ def loadTalos():
URDF_SUBPATH
=
"/talos_data/robots/"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
assert
((
robot
.
model
.
armature
[:
6
]
==
0.
).
all
())
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
assert
((
robot
.
model
.
armature
[:
6
]
==
0.
).
all
())
return
robot
...
...
@@ -72,38 +71,38 @@ def loadHyQ():
URDF_SUBPATH
=
"/hyq_description/robots/"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
return
robot
def
loadTiago
():
URDF_FILENAME
=
"tiago.urdf"
# SRDF_FILENAME = "tiago.srdf"
# SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
# SRDF_FILENAME = "tiago.srdf"
# SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
URDF_SUBPATH
=
"/tiago_description/robots/"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
# Load SRDF file
# readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
# readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
return
robot
def
loadTiagoNoHand
():
URDF_FILENAME
=
"tiago_no_hand.urdf"
# SRDF_FILENAME = "tiago.srdf"
# SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
# SRDF_FILENAME = "tiago.srdf"
# SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
URDF_SUBPATH
=
"/tiago_description/robots/"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
# Load SRDF file
# readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
# readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
return
robot
def
loadICub
(
reduced
=
True
):
if
reduced
:
URDF_FILENAME
=
"icub_reduced.urdf"
...
...
@@ -114,8 +113,7 @@ def loadICub(reduced=True):
URDF_SUBPATH
=
"/icub_description/robots/"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
return
robot
Write
Preview
Supports
Markdown
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