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
4f67fa6f
Commit
4f67fa6f
authored
6 years ago
by
Guilhem Saurel
Browse files
Options
Downloads
Patches
Plain Diff
[Tests] use getModelPath to allow build/test in different directories
parent
9aeb4e3e
No related branches found
No related tags found
2 merge requests
!4
Unittest standardization
,
!1
Added unittest code and CI setup
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
unittest/unittest_utils.py
+16
-3
16 additions, 3 deletions
unittest/unittest_utils.py
with
16 additions
and
3 deletions
unittest/unittest_utils.py
+
16
−
3
View file @
4f67fa6f
from
os.path
import
exists
,
join
import
numpy
as
np
import
numpy
as
np
import
pinocchio
import
pinocchio
from
pinocchio.robot_wrapper
import
RobotWrapper
from
pinocchio.robot_wrapper
import
RobotWrapper
def
getModelPath
(
subpath
):
for
path
in
[
'
..
'
,
'
../..
'
,
'
/opt/openrobots/share/example-robot-data
'
]:
if
exists
(
join
(
path
,
subpath
.
strip
(
'
/
'
))):
print
"
using %s as modelPath
"
%
path
return
path
raise
IOError
(
'
%s not found
'
%
(
subpath
))
def
readParamsFromSrdf
(
robot
,
SRDF_PATH
,
verbose
):
def
readParamsFromSrdf
(
robot
,
SRDF_PATH
,
verbose
):
rmodel
=
robot
.
model
rmodel
=
robot
.
model
...
@@ -26,11 +36,12 @@ def readParamsFromSrdf(robot, SRDF_PATH, verbose):
...
@@ -26,11 +36,12 @@ def readParamsFromSrdf(robot, SRDF_PATH, verbose):
return
return
def
loadTalosArm
(
modelPath
=
'
../..
'
):
def
loadTalosArm
():
URDF_FILENAME
=
"
talos_left_arm.urdf
"
URDF_FILENAME
=
"
talos_left_arm.urdf
"
URDF_SUBPATH
=
"
/talos_data/robots/
"
+
URDF_FILENAME
URDF_SUBPATH
=
"
/talos_data/robots/
"
+
URDF_FILENAME
SRDF_FILENAME
=
"
talos.srdf
"
SRDF_FILENAME
=
"
talos.srdf
"
SRDF_SUBPATH
=
"
/talos_data/srdf/
"
+
SRDF_FILENAME
SRDF_SUBPATH
=
"
/talos_data/srdf/
"
+
SRDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
])
...
@@ -39,11 +50,12 @@ def loadTalosArm(modelPath='../..'):
...
@@ -39,11 +50,12 @@ def loadTalosArm(modelPath='../..'):
return
robot
return
robot
def
loadTalos
(
modelPath
=
'
../..
'
):
def
loadTalos
():
URDF_FILENAME
=
"
talos_reduced.urdf
"
URDF_FILENAME
=
"
talos_reduced.urdf
"
SRDF_FILENAME
=
"
talos.srdf
"
SRDF_FILENAME
=
"
talos.srdf
"
SRDF_SUBPATH
=
"
/talos_data/srdf/
"
+
SRDF_FILENAME
SRDF_SUBPATH
=
"
/talos_data/srdf/
"
+
SRDF_FILENAME
URDF_SUBPATH
=
"
/talos_data/robots/
"
+
URDF_FILENAME
URDF_SUBPATH
=
"
/talos_data/robots/
"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
# Load URDF file
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
pinocchio
.
JointModelFreeFlyer
())
...
@@ -53,9 +65,10 @@ def loadTalos(modelPath='../..'):
...
@@ -53,9 +65,10 @@ def loadTalos(modelPath='../..'):
return
robot
return
robot
def
loadHyQ
(
modelPath
=
'
../..
'
):
def
loadHyQ
():
URDF_FILENAME
=
"
hyq_no_sensors.urdf
"
URDF_FILENAME
=
"
hyq_no_sensors.urdf
"
URDF_SUBPATH
=
"
/hyq_description/robots/
"
+
URDF_FILENAME
URDF_SUBPATH
=
"
/hyq_description/robots/
"
+
URDF_FILENAME
modelPath
=
getModelPath
(
URDF_SUBPATH
)
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
pinocchio
.
JointModelFreeFlyer
())
# TODO define default position inside srdf
# TODO define default position inside srdf
...
...
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