talos_navBauzil_path.py 4.63 KB
Newer Older
1
from talos_rbprm.talos_abstract import Robot  # select the robot
2
3
4
5
6
from hpp.gepetto import Viewer
from hpp.corbaserver import Client
from hpp.corbaserver import ProblemSolver
import time

7
8
9
 # 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

10
11
vMax = 0.3# linear velocity bound for the root
aMax = 0.1 # linear acceleration bound for the root
12
extraDof = 6
13
mu=0.5# coefficient of friction
14
# Creating an instance of the helper class, and loading the robot
15
rbprmBuilder = Robot()
16
17
# 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]
18
rbprmBuilder.setJointBounds ("root_joint", root_bounds)
19
20
21
# 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])
22
23

# The following lines set constraint on the valid configurations:
24
# a configuration is valid only if all feets can create a contact with the corresponding afforcances type
25
26
27
28
29
rbprmBuilder.setFilter(['talos_lleg_rom','talos_rleg_rom'])
rbprmBuilder.setAffordanceFilter('talos_lleg_rom', ['Support',])
rbprmBuilder.setAffordanceFilter('talos_rleg_rom', ['Support'])
# We also bound the rotations of the torso. (z, y, x)
rbprmBuilder.boundSO3([-4.,4.,-0.1,0.1,-0.1,0.1])
30
# Add 6 extraDOF to the problem, used to store the linear velocity and acceleration of the root
31
rbprmBuilder.client.robot.setDimensionExtraConfigSpace(extraDof)
32
# We set the bounds of this extraDof with velocity and acceleration bounds (expect on z axis)
33
34
35
rbprmBuilder.client.robot.setExtraConfigSpaceBounds([-vMax,vMax,-vMax,vMax,0,0,-aMax,aMax,-aMax,aMax,0,0])
indexECS = rbprmBuilder.getConfigSize() - rbprmBuilder.client.robot.getDimensionExtraConfigSpace()

36
# Creating an instance of HPP problem solver
37
ps = ProblemSolver( rbprmBuilder )
38
# define parameters used by various methods : 
39
40
ps.setParameter("Kinodynamic/velocityBound",vMax)
ps.setParameter("Kinodynamic/accelerationBound",aMax)
41
42
43
# 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
44
45
46
ps.setParameter("DynamicPlanner/sizeFootX",0.2)
ps.setParameter("DynamicPlanner/sizeFootY",0.12)
ps.setParameter("DynamicPlanner/friction",mu)
47
# sample only configuration with null velocity and acceleration :
48
ps.setParameter("ConfigurationShooter/sampleExtraDOF",False)
49
ps.setParameter("PathOptimization/RandomShortcut/NumberOfLoops",100)
50

51
# initialize the viewer :
52
53
54
from hpp.gepetto import ViewerFactory
vf = ViewerFactory (ps)

55
# load the module to analyse the environnement and compute the possible contact surfaces
56
57
58
from hpp.corbaserver.affordance.affordance import AffordanceTool
afftool = AffordanceTool ()
afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005])
59
# load the environment file and anaylse it :
60
afftool.loadObstacleModel ("hpp_environments", "multicontact/floor_bauzil", "planning", vf)
61
v = vf.createViewer(displayArrows = True)
62
afftool.visualiseAffordances('Support', v, v.color.lightBrown)
63
v.addLandmark(v.sceneName,1)
64
65
66

# Setting initial configuration
q_init = rbprmBuilder.getCurrentConfig ();
67
q_init[8] = 0.006761 # torso 2 position in reference config
68
69
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)
70
v (q_init)
71
ps.setInitialConfig (q_init)
72
73
74
# set goal config
rbprmBuilder.setCurrentConfig (q_init)
q_goal = q_init [::]
75
76
77
78
#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]
79
80
81
82
83
84
85
86
87
88
89
90
v(q_goal)
ps.addGoalConfig (q_goal)

# Choosing RBPRM shooter and path validation methods.
ps.selectConfigurationShooter("RbprmShooter")
ps.addPathOptimizer ("RandomShortcutDynamic")
ps.selectPathValidation("RbprmPathValidation",0.05)
# Choosing kinodynamic methods :
ps.selectSteeringMethod("RBPRMKinodynamic")
ps.selectDistance("Kinodynamic")
ps.selectPathPlanner("DynamicPlanner")

91
# Solve the planning problem :
92
t = ps.solve ()
93
print("Guide planning time : ",t)
94
95
96
97
98


# display solution : 
from hpp.gepetto import PathPlayer
pp = PathPlayer (v)
99
100
101
102
103
pp.dt=0.1
pp.displayVelocityPath(1)
v.client.gui.setVisibility("path_1_root","ALWAYS_ON_TOP")
pp.dt = 0.01
pp(1)
104

105
# move the robot out of the view before computing the contacts
106
107
108
109
q_far = q_init[::]
q_far[2] = -2
v(q_far)