Unverified Commit 241755ea authored by Fernbach Pierre's avatar Fernbach Pierre Committed by GitHub
Browse files

Merge pull request #57 from pFernbach/devel

Update tools and add scenario
parents 6cf92ff4 c9256bd6
Subproject commit 7eca9ee6c9d1c4ee20eb82272e94f9d11642053a
Subproject commit 2de34adfce816937d2403cb602261ade0c26f0cd
......@@ -27,7 +27,7 @@ q_init = q_ref[::]
fullBody.setReferenceConfig(q_ref)
fullBody.setCurrentConfig (q_init)
fullBody.setPostureWeights(fullBody.postureWeights[::]+[0]*6)
fullBody.usePosturalTaskContactCreation(True)
#fullBody.usePosturalTaskContactCreation(True)
print "Generate limb DB ..."
tStart = time.time()
......
......@@ -3,8 +3,6 @@ from hpp.gepetto import Viewer
from hpp.corbaserver import ProblemSolver
import time
vMax = 0.3# linear velocity bound for the root
aMax = 0.1# linear acceleration bound for the root
extraDof = 6
......@@ -48,13 +46,24 @@ from hpp.corbaserver.affordance.affordance import AffordanceTool
afftool = AffordanceTool ()
afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005])
afftool.loadObstacleModel ("hpp_environments", "multicontact/ground", "planning", vf)
v = vf.createViewer(displayArrows = True)
try :
v = vf.createViewer(displayArrows = True)
except Exception:
print "No viewer started !"
class FakeViewer():
def __init__(self):
return
def __call__(self,q):
return
def addLandmark(self,a,b):
return
v = FakeViewer()
#afftool.visualiseAffordances('Support', v, v.color.lightBrown)
# Setting initial configuration
q_init = rbprmBuilder.getCurrentConfig ();
q_init[3:7] = [0,0,0,1]
q_init [0:3] = [0, 0, 1.]
q_init [0:3] = [0, 0, rbprmBuilder.ref_height]
v (q_init)
ps.setInitialConfig (q_init)
# set goal config
......@@ -79,13 +88,14 @@ ps.selectPathPlanner("DynamicPlanner")
t = ps.solve ()
print "Guide planning time : ",t
pathId = 0
# display solution :
from hpp.gepetto import PathPlayer
pp = PathPlayer (v)
pp.dt=0.1
#pp.displayVelocityPath(0)
v.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP")
#v.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP")
pp.dt=0.01
#pp(0)
......
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")
......
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
# 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
......@@ -12,15 +13,15 @@ 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 limbs can create a contact with the corresponding afforcances type
# a configuration is valid only if all feets 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'])
......@@ -37,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
# 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)
......@@ -54,26 +56,27 @@ 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)
afftool.visualiseAffordances('Support', v, v.color.lightBrown)
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.
......
......@@ -4,7 +4,8 @@ from hpp.corbaserver import Client
from hpp.corbaserver import ProblemSolver
import time
Robot.urdfName +="_large_reducedROM"
Robot.urdfNameRom = ['talos_lleg_rom_reduced','talos_rleg_rom_reduced']
vMax = 0.3# linear velocity bound for the root
aMax = 0.1 # linear acceleration bound for the root
......@@ -21,9 +22,13 @@ rbprmBuilder.setJointBounds ('torso_2_joint', [0.,0.])
# The following lines set constraint on the valid configurations:
# a configuration is valid only if all limbs 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'])
rbprmBuilder.setFilter(Robot.urdfNameRom)
for rom in Robot.urdfNameRom:
rbprmBuilder.setAffordanceFilter(rom, ['Support',])
rbprmBuilder.setReferenceEndEffector('talos_lleg_rom_reduced',rbprmBuilder.ref_EE_lLeg)
rbprmBuilder.setReferenceEndEffector('talos_rleg_rom_reduced',rbprmBuilder.ref_EE_rLeg)
# We also bound the rotations of the torso. (z, y, x)
rbprmBuilder.boundSO3([-4.,4.,-0.1,0.1,-0.1,0.1])
# Add 6 extraDOF to the problem, used to store the linear velocity and acceleration of the root
......
from hpp.corbaserver.rbprm.talos_abstract import Robot
from hpp.gepetto import Viewer
from hpp.corbaserver import Client
from hpp.corbaserver import ProblemSolver
import time
from tools.sample_root_config import generate_random_conf_with_orientation
Robot.urdfName += "_large"
CONFIRM_SAMPLING = False
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 = [0,18.5,0.,24., 0.98, 0.98]
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 limbs 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'])
# We also bound the rotations of the torso. (z, y, x)
rbprmBuilder.boundSO3([-4.,4.,-0.1,0.1,-0.1,0.1])
# Add 6 extraDOF to the problem, used to store the linear velocity and acceleration of the root
rbprmBuilder.client.robot.setDimensionExtraConfigSpace(extraDof)
# We set the bounds of this extraDof with velocity and acceleration bounds (expect on z axis)
rbprmBuilder.client.robot.setExtraConfigSpaceBounds([-vMax,vMax,-vMax,vMax,0,0,-aMax,aMax,-aMax,aMax,0,0])
indexECS = rbprmBuilder.getConfigSize() - rbprmBuilder.client.robot.getDimensionExtraConfigSpace()
# Creating an instance of HPP problem solver
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)
ps.setParameter("DynamicPlanner/sizeFootX",0.2)
ps.setParameter("DynamicPlanner/sizeFootY",0.12)
ps.setParameter("DynamicPlanner/friction",mu)
# sample only configuration with null velocity and acceleration :
ps.setParameter("ConfigurationShooter/sampleExtraDOF",False)
ps.setParameter("PathOptimization/RandomShortcut/NumberOfLoops",500)
# initialize the viewer :
from hpp.gepetto import ViewerFactory
vf = ViewerFactory (ps)
# load the module to analyse the environnement and compute the possible contact surfaces
from hpp.corbaserver.affordance.affordance import AffordanceTool
afftool = AffordanceTool ()
afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005])
afftool.loadObstacleModel ("hpp_environments", "multicontact/maze_easy", "planning", vf)
v = vf.createViewer(displayArrows = True)
#afftool.visualiseAffordances('Support', v, v.color.lightBrown)
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]
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]
v(q_goal)
'''
import numpy as np
while(True):
q_init = generate_random_conf_with_orientation(rbprmBuilder,root_bounds)
v (q_init)
ps.setInitialConfig (q_init)
if CONFIRM_SAMPLING:
print "Accept?y/n"
user_in = raw_input()
if user_in == 'y':
break
else:
break
#set goal
while(True):
q_goal = generate_random_conf_with_orientation(rbprmBuilder,root_bounds)
v (q_goal)
if CONFIRM_SAMPLING:
print "Accept?y/n"
user_in = raw_input()
if user_in == 'y':
break
else:
break
ps.resetGoalConfigs()
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")
# Solve the planning problem :
ps.setMaxIterPathPlanning(50000)
t = ps.solve ()
#tic = time.time()
#v.solveAndDisplay('rm',5,0.01)
#ps.optimizePath(0)
#print "solve in " + str(time.time()-tic)
#raw_input()
print "Guide planning time : ",t
for i in range(10):
print "Optimize path, "+str(i+1)+"/10 ... "
ps.optimizePath(ps.numberPaths()-1)
pathId = ps.numberPaths()-1
# display solution :
from hpp.gepetto import PathPlayer
pp = PathPlayer (v)
pp.dt=0.1
pp.displayVelocityPath(pathId)
v.client.gui.setVisibility("path_"+str(pathId)+"_root","ALWAYS_ON_TOP")
pp.dt = 0.01
pp(pathId)
pathId = ps.numberPaths()-1
# move the robot out of the view before computing the contacts
q_far = q_init[::]
q_far[2] = -2
v(q_far)
#tStart = time.time()
#for i in range(1000):
# rbprmBuilder.isConfigValid(q_init)
#tot = time.time() - tStart
#print "avg time : ",tot/1000.
from hpp.corbaserver.rbprm.talos_abstract import Robot
from hpp.gepetto import Viewer
from hpp.corbaserver import Client
from hpp.corbaserver import ProblemSolver
import time
from tools.sample_root_config import generate_random_conf_without_orientation
Robot.urdfName += "_large"
CONFIRM_SAMPLING = False
vMax = 0.3# linear velocity bound for the root
aMax = 0.2 # 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 = [0,18.5,0.,24., 0.98, 0.98]
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 limbs 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'])
# We also bound the rotations of the torso. (z, y, x)
rbprmBuilder.boundSO3([-4.,4.,-0.1,0.1,-0.1,0.1])
# Add 6 extraDOF to the problem, used to store the linear velocity and acceleration of the root
rbprmBuilder.client.robot.setDimensionExtraConfigSpace(extraDof)
# We set the bounds of this extraDof with velocity and acceleration bounds (expect on z axis)
rbprmBuilder.client.robot.setExtraConfigSpaceBounds([-vMax,vMax,-vMax,vMax,0,0,-aMax,aMax,-aMax,aMax,0,0])
indexECS = rbprmBuilder.getConfigSize() - rbprmBuilder.client.robot.getDimensionExtraConfigSpace()
# Creating an instance of HPP problem solver
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)
ps.setParameter("DynamicPlanner/sizeFootX",0.2)
ps.setParameter("DynamicPlanner/sizeFootY",0.12)
ps.setParameter("DynamicPlanner/friction",mu)
# sample only configuration with null velocity and acceleration :
ps.setParameter("ConfigurationShooter/sampleExtraDOF",False)
ps.setParameter("PathOptimization/RandomShortcut/NumberOfLoops",500)
# initialize the viewer :
from hpp.gepetto import ViewerFactory
vf = ViewerFactory (ps)
# load the module to analyse the environnement and compute the possible contact surfaces
from hpp.corbaserver.affordance.affordance import AffordanceTool
afftool = AffordanceTool ()
afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005])
afftool.loadObstacleModel ("hpp_environments", "multicontact/maze_easy", "planning", vf)
v = vf.createViewer(displayArrows = True)
#afftool.visualiseAffordances('Support', v, v.color.lightBrown)
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]
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]
v(q_goal)
'''
import numpy as np
#set init
while(True):
q_init = generate_random_conf_without_orientation(rbprmBuilder,root_bounds)
v (q_init)
ps.setInitialConfig (q_init)
if CONFIRM_SAMPLING:
print "Accept?y/n"
user_in = raw_input()
if user_in == 'y':
break
else:
break
#set goal
while(True):
q_goal = generate_random_conf_without_orientation(rbprmBuilder,root_bounds)
v (q_goal)
if CONFIRM_SAMPLING:
print "Accept?y/n"
user_in = raw_input()
if user_in == 'y':
break
else:
break
ps.resetGoalConfigs()
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")
# Solve the planning problem :
ps.setMaxIterPathPlanning(100000)
t = ps.solve ()
#v.solveAndDisplay('rm',5,0.01)
print "Guide planning time : ",t
for i in range(10):
print "Optimize path, "+str(i+1)+"/10 ... "
ps.optimizePath(ps.numberPaths()-1)
ps.extractPath(ps.numberPaths()-1,1.,ps.pathLength(ps.numberPaths()-1)-1.)
pathId = ps.numberPaths()-1
q_init = ps.configAtParam(pathId,0)
q_goal = ps.configAtParam(pathId,ps.pathLength(pathId))
# display solution :
from hpp.gepetto import PathPlayer
pp = PathPlayer (v)
pp.dt=0.1
pp.displayVelocityPath(pathId)
v.client.gui.setVisibility("path_"+str(pathId)+"_root","ALWAYS_ON_TOP")
pp.dt = 0.01
pp(pathId)
# move the robot out of the view before computing the contacts
q_far = q_init[::]
q_far[2] = -2
v(q_far)
#tStart = time.time()
#for i in range(1000):
# rbprmBuilder.isConfigValid(q_init)
#tot = time.time() - tStart
#print "avg time : ",tot/1000.
......@@ -8,8 +8,6 @@ import random
import time
statusFilename = "/res/infos.log"
fullBody = Robot ()
# Set the bounds for the root
fullBody.setJointBounds ("root_joint", [-0.3,0.3, -0.3, 0.3, 0.85, 1.05])
......@@ -74,9 +72,9 @@ tStart = time.time()
nbSamples = 10
fullBody.addLimb(fullBody.rLegId,fullBody.rleg,fullBody.rfoot,fullBody.rLegOffset,fullBody.rLegNormal, fullBody.rLegx, fullBody.rLegy, nbSamples, "static", 0.01,kinematicConstraintsPath=fullBody.rLegKinematicConstraints,kinematicConstraintsMin = 0.7)
fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True)
#fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True)
fullBody.addLimb(fullBody.lLegId,fullBody.lleg,fullBody.lfoot,fullBody.lLegOffset,fullBody.rLegNormal, fullBody.lLegx, fullBody.lLegy, nbSamples, "static", 0.01,kinematicConstraintsPath=fullBody.lLegKinematicConstraints,kinematicConstraintsMin = 0.7)
fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True)
#fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True)
tGenerate = time.time() - tStart
......@@ -108,12 +106,12 @@ else:
print "Contact generation failed."
f = open(statusFilename,"w")
f.write("q_init= "+str(s0.q())+"\n")
f.write("q_goal= "+str(s1.q())+"\n")
f.write("cg_success: "+str(cg_success)+"\n")
f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n")
f.close()
#f = open(statusFilename,"w")
#f.write("q_init= "+str(s0.q())+"\n")
#f.write("q_goal= "+str(s1.q())+"\n")
#f.write("cg_success: "+str(cg_success)+"\n")
#f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n")
#f.close()
# put back original bounds for wholebody methods
......
from hpp.corbaserver.rbprm.talos import Robot
from hpp.gepetto import Viewer
from tools.display_tools import *
import time
print "Plan guide trajectory ..."
import talos_navBauzil_path as tp
print "Done."
import time
Robot.urdfSuffix += "_safeFeet"
pId = tp.ps.numberPaths() -1
fullBody = Robot ()
# Set the bounds for the root, take slightly larger bounding box than during root planning
root_bounds = tp.root_bounds[::]
root_bounds[0] -= 0.2
root_bounds[1] += 0.2
root_bounds[2] -= 0.2
root_bounds[3] += 0.2
root_bounds[-1] = 1.2
root_bounds[-2] = 0.8