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
a1ced670
Commit
a1ced670
authored
5 years ago
by
Guilhem Saurel
Browse files
Options
Downloads
Plain Diff
Merge branch 'devel' into 'devel'
some models don't have robot parameters, fix
#13
See merge request
!12
parents
ec0673d7
6e02372e
No related branches found
Branches containing commit
No related tags found
1 merge request
!12
some models don't have robot parameters, fix #13
Pipeline
#5809
passed
5 years ago
Stage: test
Changes
1
Pipelines
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
example_robot_data/robots_loader.py
+7
-5
7 additions, 5 deletions
example_robot_data/robots_loader.py
with
7 additions
and
5 deletions
example_robot_data/robots_loader.py
+
7
−
5
View file @
a1ced670
...
...
@@ -2,6 +2,7 @@ import sys
from
os.path
import
dirname
,
exists
,
join
import
numpy
as
np
import
pinocchio
from
pinocchio.robot_wrapper
import
RobotWrapper
...
...
@@ -22,10 +23,11 @@ def getModelPath(subpath, printmsg=False):
raise
IOError
(
'
%s not found
'
%
(
subpath
))
def
readParamsFromSrdf
(
robot
,
SRDF_PATH
,
verbose
):
def
readParamsFromSrdf
(
robot
,
SRDF_PATH
,
verbose
,
has_rotor_parameters
=
True
):
rmodel
=
robot
.
model
pinocchio
.
loadRotorParameters
(
rmodel
,
SRDF_PATH
,
verbose
)
if
has_rotor_parameters
:
pinocchio
.
loadRotorParameters
(
rmodel
,
SRDF_PATH
,
verbose
)
rmodel
.
armature
=
np
.
multiply
(
rmodel
.
rotorInertia
.
flat
,
np
.
square
(
rmodel
.
rotorGearRatio
.
flat
))
pinocchio
.
loadReferenceConfigurations
(
rmodel
,
SRDF_PATH
,
verbose
)
robot
.
q0
.
flat
[:]
=
rmodel
.
referenceConfigurations
[
"
half_sitting
"
].
copy
()
...
...
@@ -138,7 +140,7 @@ def loadHyQ():
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
,
False
)
# Add the free-flyer joint limits
addFreeFlyerJointLimits
(
robot
)
return
robot
...
...
@@ -156,7 +158,7 @@ def loadSolo(solo=True):
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
,
False
)
# Add the free-flyer joint limits
addFreeFlyerJointLimits
(
robot
)
return
robot
...
...
@@ -200,7 +202,7 @@ def loadICub(reduced=True):
# Load URDF file
robot
=
RobotWrapper
.
BuildFromURDF
(
modelPath
+
URDF_SUBPATH
,
[
modelPath
],
pinocchio
.
JointModelFreeFlyer
())
# Load SRDF file
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
)
readParamsFromSrdf
(
robot
,
modelPath
+
SRDF_SUBPATH
,
False
,
False
)
# Add the free-flyer joint limits
addFreeFlyerJointLimits
(
robot
)
return
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