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
Guilhem Saurel
hpp-rbprm-corba
Commits
2f445727
Commit
2f445727
authored
Nov 15, 2019
by
Pierre Fernbach
Browse files
[demo] update talos_navBauzil scripts
parent
b54e60d0
Changes
2
Hide whitespace changes
Inline
Side-by-side
script/scenarios/demos/talos_navBauzil.py
View file @
2f445727
from
hpp.corbaserver.rbprm.talos
import
Robot
from
hpp.corbaserver.rbprm.talos
import
Robot
# select the robot
from
hpp.gepetto
import
Viewer
from
hpp.corbaserver.rbprm.tools.display_tools
import
*
import
time
print
"Plan guide trajectory ..."
import
talos_navBauzil_path
as
tp
import
talos_navBauzil_path
as
tp
# load the guide planning script
print
"Done."
import
time
Robot
.
urdfSuffix
+=
"_safeFeet"
...
...
@@ -30,7 +30,7 @@ ps.setParameter("Kinodynamic/accelerationBound",tp.aMax)
v
=
tp
.
Viewer
(
ps
,
viewerClient
=
tp
.
v
.
client
,
displayCoM
=
True
)
# load a reference configuration
q_ref
=
fullBody
.
referenceConfig
[::]
+
[
0
,
0
,
0
,
0
,
0
,
0
]
q_ref
=
fullBody
.
referenceConfig
_elbowsUp
[::]
+
[
0
,
0
,
0
,
0
,
0
,
0
]
q_init
=
q_ref
[::]
fullBody
.
setReferenceConfig
(
q_ref
)
fullBody
.
setCurrentConfig
(
q_init
)
...
...
@@ -39,8 +39,9 @@ fullBody.usePosturalTaskContactCreation(True)
print
"Generate limb DB ..."
tStart
=
time
.
time
()
# generate databases :
nbSamples
=
10000
# generate databases :
nbSamples
=
100000
fullBody
.
addLimb
(
fullBody
.
rLegId
,
fullBody
.
rleg
,
fullBody
.
rfoot
,
fullBody
.
rLegOffset
,
fullBody
.
rLegNormal
,
fullBody
.
rLegx
,
fullBody
.
rLegy
,
nbSamples
,
"fixedStep06"
,
0.01
,
kinematicConstraintsPath
=
fullBody
.
rLegKinematicConstraints
,
kinematicConstraintsMin
=
0.85
)
#fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True)
#fullBody.saveLimbDatabase(rLegId, "./db/talos_rLeg_walk.db")
...
...
script/scenarios/demos/talos_navBauzil_path.py
View file @
2f445727
from
hpp.corbaserver.rbprm.talos_abstract
import
Robot
from
hpp.corbaserver.rbprm.talos_abstract
import
Robot
# select the robot
from
hpp.gepetto
import
Viewer
from
hpp.corbaserver
import
Client
from
hpp.corbaserver
import
ProblemSolver
import
time
Robot
.
urdfName
+=
"_large"
# select the reduced model of the robot used for the guide planning
Robot
.
urdfName
+=
"_large"
#the "large" one use a conservative bounding box for the hips, taking in account the swinging motion made during a walk
vMax
=
0.3
# linear velocity bound for the root
aMax
=
0.1
# linear acceleration bound for the root
extraDof
=
6
mu
=
0.5
# coefficient of friction
# Creating an instance of the helper class, and loading the robot
rbprmBuilder
=
Robot
()
# Define bounds for the root : bounding box of the scenario
root_bounds
=
[
-
1.5
,
3
,
0.
,
3.3
,
0.98
,
0.98
]
# Define bounds for the root : bounding box of the scenario
[-x,+x,-y,+y,-z,+z]
root_bounds
=
[
-
1.5
,
4
,
0.
,
3.3
,
rbprmBuilder
.
ref_height
,
rbprmBuilder
.
ref_height
]
rbprmBuilder
.
setJointBounds
(
"root_joint"
,
root_bounds
)
# As this scenario only consider walking, we fix the DOF of the torso :
rbprmBuilder
.
setJointBounds
(
'torso_1_joint'
,
[
0
,
0
])
rbprmBuilder
.
setJointBounds
(
'torso_2_joint'
,
[
0.006761
,
0.006761
])
# The following lines set constraint on the valid configurations:
# a configuration is valid only if all
limb
s can create a contact with the corresponding afforcances type
# a configuration is valid only if all
feet
s can create a contact with the corresponding afforcances type
rbprmBuilder
.
setFilter
([
'talos_lleg_rom'
,
'talos_rleg_rom'
])
rbprmBuilder
.
setAffordanceFilter
(
'talos_lleg_rom'
,
[
'Support'
,])
rbprmBuilder
.
setAffordanceFilter
(
'talos_rleg_rom'
,
[
'Support'
])
...
...
@@ -36,8 +38,9 @@ ps = ProblemSolver( rbprmBuilder )
# define parameters used by various methods :
ps
.
setParameter
(
"Kinodynamic/velocityBound"
,
vMax
)
ps
.
setParameter
(
"Kinodynamic/accelerationBound"
,
aMax
)
# force the orientation of the trunk to match the direction of the motion
#ps.setParameter("Kinodynamic/forceYawOrientation",True)
# force the orientation of the trunk to match the direction of the motion:
ps
.
setParameter
(
"Kinodynamic/forceYawOrientation"
,
True
)
# size of the feet and friction coefficient used to check to the dynamic feasibility of the guide path
ps
.
setParameter
(
"DynamicPlanner/sizeFootX"
,
0.2
)
ps
.
setParameter
(
"DynamicPlanner/sizeFootY"
,
0.12
)
ps
.
setParameter
(
"DynamicPlanner/friction"
,
mu
)
...
...
@@ -53,6 +56,7 @@ vf = ViewerFactory (ps)
from
hpp.corbaserver.affordance.affordance
import
AffordanceTool
afftool
=
AffordanceTool
()
afftool
.
setAffordanceConfig
(
'Support'
,
[
0.5
,
0.03
,
0.00005
])
# load the environment file and anaylse it :
afftool
.
loadObstacleModel
(
"hpp_environments"
,
"multicontact/floor_bauzil"
,
"planning"
,
vf
)
v
=
vf
.
createViewer
(
displayArrows
=
True
)
afftool
.
visualiseAffordances
(
'Support'
,
v
,
v
.
color
.
lightBrown
)
...
...
@@ -61,18 +65,18 @@ v.addLandmark(v.sceneName,1)
# Setting initial configuration
q_init
=
rbprmBuilder
.
getCurrentConfig
();
q_init
[
8
]
=
0.006761
# torso 2 position in reference config
q_init
[
0
:
3
]
=
[
-
0.9
,
1.
5
,
0.98
]
q_init
[
-
6
:
-
3
]
=
[
0.07
,
0
,
0
]
q_init
[
0
:
3
]
=
[
-
0.9
,
1.
7
,
rbprmBuilder
.
ref_height
]
# root x,y,z position
q_init
[
-
6
:
-
3
]
=
[
0.07
,
0
,
0
]
# Used to constraint the initial orientation when forceYawOrientation = True, expressed as a 3D vector (x,y,z)
v
(
q_init
)
ps
.
setInitialConfig
(
q_init
)
# set goal config
rbprmBuilder
.
setCurrentConfig
(
q_init
)
q_goal
=
q_init
[::]
q_goal
[
0
:
3
]
=
[
2
,
2.6
,
0.98
]
q_goal
[
-
6
:
-
3
]
=
[
0.1
,
0
,
0
]
#q_goal[0:3] = [2,2.6,0.98]
#q_goal[-6:-3] = [0.1,0,0]
q_goal
[
0
:
3
]
=
[
3.6
,
1.2
,
rbprmBuilder
.
ref_height
]
q_goal
[
-
6
:
-
3
]
=
[
0
,
-
0.1
,
0
]
v
(
q_goal
)
ps
.
addGoalConfig
(
q_goal
)
# Choosing RBPRM shooter and path validation methods.
...
...
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