diff --git a/script/scenarios/memmo/anymal_circle.py b/script/scenarios/memmo/anymal_circle.py new file mode 100644 index 0000000000000000000000000000000000000000..854b73f8bce7731d2b7dc5dc118a52962f848c1b --- /dev/null +++ b/script/scenarios/memmo/anymal_circle.py @@ -0,0 +1,182 @@ +from hpp.corbaserver.rbprm.anymal import Robot +from hpp.gepetto import Viewer +from tools.display_tools import * +import time +print "Plan guide trajectory ..." +import anymal_circle_path as tp +print "Done." +import time +statusFilename = tp.statusFilename +pId = 0 +f = open(statusFilename,"a") +if tp.ps.numberPaths() > 0 : + print "Path planning OK." + f.write("Planning_success: True"+"\n") + f.close() +else : + print "Error during path planning" + f.write("Planning_success: False"+"\n") + f.close() + import sys + sys.exit(1) + + +fullBody = Robot () +root_bounds = tp.root_bounds +root_bounds[-1] = 0.6 +root_bounds[-2] = 0.3 +# Set the bounds for the root +fullBody.setJointBounds ("root_joint", root_bounds) +## reduce bounds on joints along x, to put conservative condition on the contact generation for sideway steps +fullBody.setVeryConstrainedJointsBounds() +# add the 6 extraDof for velocity and acceleration (see *_path.py script) +fullBody.client.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.client.robot.setExtraConfigSpaceBounds([-tp.vMax,tp.vMax,-tp.vMax,tp.vMax,0,0,-tp.aMax,tp.aMax,-tp.aMax,tp.aMax,0,0]) +ps = tp.ProblemSolver( fullBody ) +ps.setParameter("Kinodynamic/velocityBound",tp.vMax) +ps.setParameter("Kinodynamic/accelerationBound",tp.aMax) +#load the viewer +try : + v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = 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() + + +# load a reference configuration +q_ref = fullBody.referenceConfig[::]+[0]*6 +#q_ref = fullBody.referenceConfig_legsApart[::]+[0]*6 +q_init = q_ref[::] +fullBody.setReferenceConfig(q_ref) +fullBody.setPostureWeights(fullBody.postureWeights[::]+[0]*6) +fullBody.usePosturalTaskContactCreation(True) + +""" +if abs(tp.q_goal[1]) <= abs(tp.q_goal[0]) : + heuristicR = "fixedStep08" + heuristicL = "fixedStep08" + print "Use weight for straight walk" + fullBody.usePosturalTaskContactCreation(True) +else : + print "Use weight for straff walk" + if tp.q_goal[1] < 0 : + print "start with right leg" + heuristicL = "static" + heuristicR = "fixedStep06" + else: + print "start with left leg" + heuristicR = "static" + heuristicL = "fixedStep06" +""" + +fullBody.setCurrentConfig (q_init) + +print "Generate limb DB ..." +tStart = time.time() +# generate databases : +""" +nbSamples = 100000 +fullBody.addLimb(fullBody.rLegId,fullBody.rleg,fullBody.rfoot,fullBody.rLegOffset,fullBody.rLegNormal, fullBody.rLegx, fullBody.rLegy, nbSamples, heuristicR, 0.01,kinematicConstraintsPath=fullBody.rLegKinematicConstraints,kinematicConstraintsMin = 0.85) +fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True) +fullBody.addLimb(fullBody.lLegId,fullBody.lleg,fullBody.lfoot,fullBody.lLegOffset,fullBody.rLegNormal, fullBody.lLegx, fullBody.lLegy, nbSamples, heuristicL, 0.01,kinematicConstraintsPath=fullBody.lLegKinematicConstraints,kinematicConstraintsMin = 0.85) +fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True) +""" +fullBody.loadAllLimbs("fixedStep04","ReferenceConfiguration") + +tGenerate = time.time() - tStart +print "Done." +print "Databases generated in : "+str(tGenerate)+" s" + +#define initial and final configurations : +configSize = fullBody.getConfigSize() -fullBody.client.robot.getDimensionExtraConfigSpace() + +q_init[0:7] = tp.ps.configAtParam(pId,0)[0:7] # use this to get the correct orientation +q_goal = q_init[::]; q_goal[0:7] = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[0:7] +vel_init = tp.ps.configAtParam(pId,0)[tp.indexECS:tp.indexECS+3] +acc_init = tp.ps.configAtParam(pId,0)[tp.indexECS+3:tp.indexECS+6] +vel_goal = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[tp.indexECS:tp.indexECS+3] +acc_goal = [0,0,0] + +robTreshold = 3 +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = vel_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = vel_goal[::] +q_goal[configSize+3:configSize+6] = [0,0,0] + + +q_init[2] = q_ref[2] +q_goal[2] = q_ref[2] + + +fullBody.setStaticStability(True) +fullBody.setCurrentConfig (q_init) +v(q_init) + +fullBody.setCurrentConfig (q_goal) +v(q_goal) + +v.addLandmark('anymal/base_0',0.3) +v(q_init) +#fullBody.setReferenceConfig(fullBody.referenceConfig_legsApart[::]+[0]*6) + + +# specify the full body configurations as start and goal state of the problem + +normals = [[0.,0.,1.] for _ in range(4)] +if q_goal[1] < 0: # goal on the right side of the circle, start motion with right leg first + fullBody.setStartState(q_init,[fullBody.rArmId,fullBody.rLegId,fullBody.lArmId,fullBody.lLegId],normals) + fullBody.setEndState(q_goal,[fullBody.rArmId,fullBody.rLegId,fullBody.lArmId,fullBody.lLegId],normals) +else : + fullBody.setStartState(q_init,[fullBody.lArmId,fullBody.lLegId,fullBody.rArmId,fullBody.rLegId],normals) + fullBody.setEndState(q_goal,[fullBody.lArmId,fullBody.lLegId,fullBody.rArmId,fullBody.rLegId],normals) + +print "Generate contact plan ..." +tStart = time.time() +configs = fullBody.interpolate(0.002,pathId=pId,robustnessTreshold = 1, filterStates = True,quasiStatic=True) +tInterpolateConfigs = time.time() - tStart +print "Done." +print "Contact plan generated in : "+str(tInterpolateConfigs)+" s" +print "number of configs :", len(configs) +#raw_input("Press Enter to display the contact sequence ...") +#displayContactSequence(v,configs) + + +if len(configs) < 2 : + cg_success = False + print "Error during contact generation." +else: + cg_success = True + print "Contact generation Done." +if abs(configs[-1][0] - tp.q_goal[0]) < 0.01 and abs(configs[-1][1]- tp.q_goal[1]) < 0.01 and (len(fullBody.getContactsVariations(len(configs)-2,len(configs)-1))==1): + print "Contact generation successful." + cg_reach_goal = True +else: + print "Contact generation failed to reach the goal." + cg_reach_goal = False +if len(configs) > 10 : + cg_too_many_states = True + cg_success = False + print "Discarded contact sequence because it was too long." +else: + cg_too_many_states = False + +f = open(statusFilename,"a") +f.write("cg_success: "+str(cg_success)+"\n") +f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n") +f.write("cg_too_many_states: "+str(cg_too_many_states)+"\n") +f.close() + +if (not cg_success) or cg_too_many_states or (not cg_reach_goal): + import sys + sys.exit(1) + +# put back original bounds for wholebody methods +fullBody.resetJointsBounds() diff --git a/script/scenarios/memmo/anymal_circle_oriented.py b/script/scenarios/memmo/anymal_circle_oriented.py new file mode 100644 index 0000000000000000000000000000000000000000..cc0a5a7dc5e8a6bd6810a96e5e9d5bdeae250f13 --- /dev/null +++ b/script/scenarios/memmo/anymal_circle_oriented.py @@ -0,0 +1,187 @@ +from hpp.corbaserver.rbprm.anymal import Robot +from hpp.gepetto import Viewer +from tools.display_tools import * +import time +print "Plan guide trajectory ..." +import anymal_circle_oriented_path as tp +print "Done." +import time +statusFilename = tp.statusFilename +pId = 0 +f = open(statusFilename,"a") +if tp.ps.numberPaths() > 0 : + print "Path planning OK." + f.write("Planning_success: True"+"\n") + f.close() +else : + print "Error during path planning" + f.write("Planning_success: False"+"\n") + f.close() + import sys + sys.exit(1) + + +fullBody = Robot () +root_bounds = tp.root_bounds +root_bounds[-1] = 0.6 +root_bounds[-2] = 0.3 +# Set the bounds for the root +fullBody.setJointBounds ("root_joint", root_bounds) +## reduce bounds on joints along x, to put conservative condition on the contact generation for sideway steps +fullBody.setVeryConstrainedJointsBounds() +fullBody.setJointBounds('LF_HAA',[-0.2,0.2]) +fullBody.setJointBounds('RF_HAA',[-0.2,0.2]) +fullBody.setJointBounds('LH_HAA',[-0.2,0.2]) +fullBody.setJointBounds('RH_HAA',[-0.2,0.2]) + +# add the 6 extraDof for velocity and acceleration (see *_path.py script) +fullBody.client.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.client.robot.setExtraConfigSpaceBounds([-tp.vMax,tp.vMax,-tp.vMax,tp.vMax,0,0,-tp.aMax,tp.aMax,-tp.aMax,tp.aMax,0,0]) +ps = tp.ProblemSolver( fullBody ) +ps.setParameter("Kinodynamic/velocityBound",tp.vMax) +ps.setParameter("Kinodynamic/accelerationBound",tp.aMax) +#load the viewer +try : + v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = 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() + + +# load a reference configuration +q_ref = fullBody.referenceConfig[::]+[0]*6 +#q_ref = fullBody.referenceConfig_legsApart[::]+[0]*6 +q_init = q_ref[::] +fullBody.setReferenceConfig(q_ref) +fullBody.setPostureWeights(fullBody.postureWeights[::]+[0]*6) +fullBody.usePosturalTaskContactCreation(True) + +""" +if abs(tp.q_goal[1]) <= abs(tp.q_goal[0]) : + heuristicR = "fixedStep08" + heuristicL = "fixedStep08" + print "Use weight for straight walk" + fullBody.usePosturalTaskContactCreation(True) +else : + print "Use weight for straff walk" + if tp.q_goal[1] < 0 : + print "start with right leg" + heuristicL = "static" + heuristicR = "fixedStep06" + else: + print "start with left leg" + heuristicR = "static" + heuristicL = "fixedStep06" +""" + +fullBody.setCurrentConfig (q_init) + +print "Generate limb DB ..." +tStart = time.time() +# generate databases : +""" +nbSamples = 100000 +fullBody.addLimb(fullBody.rLegId,fullBody.rleg,fullBody.rfoot,fullBody.rLegOffset,fullBody.rLegNormal, fullBody.rLegx, fullBody.rLegy, nbSamples, heuristicR, 0.01,kinematicConstraintsPath=fullBody.rLegKinematicConstraints,kinematicConstraintsMin = 0.85) +fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True) +fullBody.addLimb(fullBody.lLegId,fullBody.lleg,fullBody.lfoot,fullBody.lLegOffset,fullBody.rLegNormal, fullBody.lLegx, fullBody.lLegy, nbSamples, heuristicL, 0.01,kinematicConstraintsPath=fullBody.lLegKinematicConstraints,kinematicConstraintsMin = 0.85) +fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True) +""" +fullBody.loadAllLimbs("fixedStep04") + +tGenerate = time.time() - tStart +print "Done." +print "Databases generated in : "+str(tGenerate)+" s" + +#define initial and final configurations : +configSize = fullBody.getConfigSize() -fullBody.client.robot.getDimensionExtraConfigSpace() + +q_init[0:7] = tp.ps.configAtParam(pId,0)[0:7] # use this to get the correct orientation +q_goal = q_init[::]; q_goal[0:7] = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[0:7] +vel_init = tp.ps.configAtParam(pId,0)[tp.indexECS:tp.indexECS+3] +acc_init = tp.ps.configAtParam(pId,0)[tp.indexECS+3:tp.indexECS+6] +vel_goal = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[tp.indexECS:tp.indexECS+3] +acc_goal = [0,0,0] + +robTreshold = 3 +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = vel_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = vel_goal[::] +q_goal[configSize+3:configSize+6] = [0,0,0] + + +q_init[2] = q_ref[2] +q_goal[2] = q_ref[2] + + +fullBody.setStaticStability(True) +fullBody.setCurrentConfig (q_init) +v(q_init) + +fullBody.setCurrentConfig (q_goal) +v(q_goal) + +v.addLandmark('anymal/base_0',0.3) +v(q_init) +#fullBody.setReferenceConfig(fullBody.referenceConfig_legsApart[::]+[0]*6) + + +# specify the full body configurations as start and goal state of the problem + +normals = [[0.,0.,1.] for _ in range(4)] +if q_goal[1] < 0: # goal on the right side of the circle, start motion with right leg first + fullBody.setStartState(q_init,[fullBody.rArmId,fullBody.rLegId,fullBody.lArmId,fullBody.lLegId],normals) + fullBody.setEndState(q_goal,[fullBody.rArmId,fullBody.rLegId,fullBody.lArmId,fullBody.lLegId],normals) +else : + fullBody.setStartState(q_init,[fullBody.lArmId,fullBody.lLegId,fullBody.rArmId,fullBody.rLegId],normals) + fullBody.setEndState(q_goal,[fullBody.lArmId,fullBody.lLegId,fullBody.rArmId,fullBody.rLegId],normals) + +print "Generate contact plan ..." +tStart = time.time() +configs = fullBody.interpolate(0.001,pathId=pId,robustnessTreshold = 1, filterStates = True,quasiStatic=True) +tInterpolateConfigs = time.time() - tStart +print "Done." +print "Contact plan generated in : "+str(tInterpolateConfigs)+" s" +print "number of configs :", len(configs) +#raw_input("Press Enter to display the contact sequence ...") +#displayContactSequence(v,configs) + + +if len(configs) < 2 : + cg_success = False + print "Error during contact generation." +else: + cg_success = True + print "Contact generation Done." +if abs(configs[-1][0] - tp.q_goal[0]) < 0.01 and abs(configs[-1][1]- tp.q_goal[1]) < 0.01 and (len(fullBody.getContactsVariations(len(configs)-2,len(configs)-1))==1): + print "Contact generation successful." + cg_reach_goal = True +else: + print "Contact generation failed to reach the goal." + cg_reach_goal = False +if len(configs) > 50 : + cg_too_many_states = True + cg_success = False + print "Discarded contact sequence because it was too long." +else: + cg_too_many_states = False + +f = open(statusFilename,"a") +f.write("cg_success: "+str(cg_success)+"\n") +f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n") +f.write("cg_too_many_states: "+str(cg_too_many_states)+"\n") +f.close() + +if (not cg_success) or cg_too_many_states or (not cg_reach_goal): + import sys + sys.exit(1) + +# put back original bounds for wholebody methods +fullBody.resetJointsBounds() diff --git a/script/scenarios/memmo/anymal_circle_oriented_path.py b/script/scenarios/memmo/anymal_circle_oriented_path.py new file mode 100644 index 0000000000000000000000000000000000000000..14fc6ae6e911219cee83008037279306ef28478e --- /dev/null +++ b/script/scenarios/memmo/anymal_circle_oriented_path.py @@ -0,0 +1,142 @@ +from hpp.corbaserver.rbprm.anymal_abstract import Robot +from hpp.gepetto import Viewer +from hpp.corbaserver import ProblemSolver +import numpy as np +import time +statusFilename = "/res/infos.log" +from pinocchio import Quaternion + +vMax = 0.5# linear velocity bound for the root +vInit = 0.05# initial / final velocity to fix the direction +vGoal = 0.01 +aMax = 0.05# 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 +# 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 = [-2,2, -2, 2, 0.4, 0.5] +rbprmBuilder.setJointBounds ("root_joint", root_bounds) + +# 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(rbprmBuilder.urdfNameRom) +for rom in rbprmBuilder.urdfNameRom : + rbprmBuilder.setAffordanceFilter(rom, ['Support']) + +# We also bound the rotations of the torso. (z, y, x) +rbprmBuilder.boundSO3([-1.7,1.7,-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) +ps.setParameter("DynamicPlanner/sizeFootX",0.01) +ps.setParameter("DynamicPlanner/sizeFootY",0.01) +ps.setParameter("DynamicPlanner/friction",mu) +ps.setParameter("Kinodynamic/forceYawOrientation",True) +# sample only configuration with null velocity and acceleration : +ps.setParameter("ConfigurationShooter/sampleExtraDOF",False) + +# 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/ground", "planning", vf) +try : + v = vf.createViewer(displayArrows = True) +except Exception: + print "No viewer started !" + class FakeViewer(): + def __init__(self): + return + def __call__(self,q): + return + v = FakeViewer() + +#afftool.visualiseAffordances('Support', v, v.color.lightBrown) + +q_init = rbprmBuilder.getCurrentConfig (); +q_init[0:3] = [0,0,0.465] +q_init[3:7] = [0,0,0,1] + +# sample random position on a circle of radius 2m +q_init[-6] = vInit +# sample random position on a circle of radius 2m + +radius = 1. +import random +random.seed() +#alpha = random.uniform(0.,2.*np.pi) +alpha = random.uniform(0.,2.*np.pi) +print "Test on a circle, alpha = ",alpha +q_goal = q_init[::] +q_goal [0:3] = [radius*np.sin(alpha), -radius*np.cos(alpha), 0.465] +# set final orientation to be along the circle : +vx = np.matrix([1,0,0]).T +v_goal = np.matrix([q_goal[0],q_goal[1],0]).T +quat = Quaternion.FromTwoVectors(vx,v_goal) +q_goal[3:7] = quat.coeffs().T.tolist()[0] +# set final velocity to fix the orientation : +q_goal[-6] = vGoal*np.sin(alpha) +q_goal[-5] = -vGoal*np.cos(alpha) +v(q_goal) +print "initial root position : ",q_init +print "final root position : ",q_goal +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +# write problem in files : +f = open(statusFilename,"w") +f.write("q_init= "+str(q_init)+"\n") +f.write("q_goal= "+str(q_goal)+"\n") +f.close() + + +# Choosing RBPRM shooter and path validation methods. +ps.selectConfigurationShooter("RbprmShooter") +ps.selectPathValidation("RbprmPathValidation",0.05) +# Choosing kinodynamic methods : +ps.selectSteeringMethod("RBPRMKinodynamic") +ps.selectDistance("Kinodynamic") +ps.selectPathPlanner("DynamicPlanner") + + +# Solve the planning problem : +success = ps.client.problem.prepareSolveStepByStep() + +if not success: + print "planning failed." + import sys + sys.exit(1) + +ps.client.problem.finishSolveStepByStep() + +try : + # 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") + pp.dt=0.01 + #pp(0) +except Exception: + pass + +# move the robot out of the view before computing the contacts +q_far = q_init[::] +q_far[2] = -2 +v(q_far) + diff --git a/script/scenarios/memmo/anymal_circle_path.py b/script/scenarios/memmo/anymal_circle_path.py new file mode 100644 index 0000000000000000000000000000000000000000..18bf85a77f38859c36dd0f22dd8b448699303a55 --- /dev/null +++ b/script/scenarios/memmo/anymal_circle_path.py @@ -0,0 +1,121 @@ +from hpp.corbaserver.rbprm.anymal_abstract import Robot +from hpp.gepetto import Viewer +from hpp.corbaserver import ProblemSolver +import numpy as np +import time +statusFilename = "/res/infos.log" + + +vMax = 0.3# linear velocity bound for the root +aMax = 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 +# 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 = [-2,2, -2, 2, 0.4, 0.5] +rbprmBuilder.setJointBounds ("root_joint", root_bounds) + +# 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(rbprmBuilder.urdfNameRom) +for rom in rbprmBuilder.urdfNameRom : + rbprmBuilder.setAffordanceFilter(rom, ['Support']) + +# We also bound the rotations of the torso. (z, y, x) +rbprmBuilder.boundSO3([-1.7,1.7,-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) +ps.setParameter("DynamicPlanner/sizeFootX",0.01) +ps.setParameter("DynamicPlanner/sizeFootY",0.01) +ps.setParameter("DynamicPlanner/friction",mu) +# sample only configuration with null velocity and acceleration : +ps.setParameter("ConfigurationShooter/sampleExtraDOF",False) + +# 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/ground", "planning", vf) +try : + v = vf.createViewer(displayArrows = True) +except Exception: + print "No viewer started !" + class FakeViewer(): + def __init__(self): + return + def __call__(self,q): + return + v = FakeViewer() + +#afftool.visualiseAffordances('Support', v, v.color.lightBrown) + +q_init = rbprmBuilder.getCurrentConfig (); +q_init[0:3] = [0,0,0.465] +q_init[3:7] = [0,0,0,1] + +# sample random position on a circle of radius 2m + +radius = 0.15 +import random +random.seed() +alpha = random.uniform(0.,2.*np.pi) +print "Test on a circle, alpha = ",alpha +q_goal = q_init[::] +q_goal [0:3] = [radius*np.sin(alpha), -radius*np.cos(alpha), 0.465] + +print "initial root position : ",q_init[0:3] +print "final root position : ",q_goal[0:3] +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +# write problem in files : +f = open(statusFilename,"w") +f.write("q_init= "+str(q_init)+"\n") +f.write("q_goal= "+str(q_goal)+"\n") +f.close() + + +# Choosing RBPRM shooter and path validation methods. +ps.selectConfigurationShooter("RbprmShooter") +ps.selectPathValidation("RbprmPathValidation",0.05) +# Choosing kinodynamic methods : +ps.selectSteeringMethod("RBPRMKinodynamic") +ps.selectDistance("Kinodynamic") +ps.selectPathPlanner("DynamicPlanner") + +# Solve the planning problem : +t = ps.solve () +print "Guide planning time : ",t + +try : + # 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") + pp.dt=0.01 + #pp(0) +except Exception: + pass + +# move the robot out of the view before computing the contacts +q_far = q_init[::] +q_far[2] = -2 +v(q_far) + diff --git a/script/scenarios/memmo/anymal_platform_random.py b/script/scenarios/memmo/anymal_platform_random.py new file mode 100644 index 0000000000000000000000000000000000000000..9ba5fb92a5b270ff9e2839bb70a46895ded6adca --- /dev/null +++ b/script/scenarios/memmo/anymal_platform_random.py @@ -0,0 +1,143 @@ +from hpp.corbaserver.rbprm.anymal import Robot +from hpp.gepetto import Viewer +from tools.display_tools import * +import time +print "Plan guide trajectory ..." +import scenarios.memmo.anymal_platform_random_path as tp +#Robot.urdfSuffix += "_safeFeet" +statusFilename = tp.statusFilename +pId = 0 +f = open(statusFilename,"a") +if tp.ps.numberPaths() > 0 : + print "Path planning OK." + f.write("Planning_success: True"+"\n") + f.close() +else : + print "Error during path planning" + f.write("Planning_success: False"+"\n") + f.close() + import sys + sys.exit(1) + +fullBody = Robot () + +# Set the bounds for the root +rootBounds = tp.rootBounds[::] +rootBounds[-2] -= 0.2 +rootBounds[0] -= 0.2 +rootBounds[1] += 0.2 +rootBounds[2] -= 0.2 +rootBounds[3] += 0.2 +fullBody.setJointBounds ("root_joint", rootBounds) +fullBody.setVeryConstrainedJointsBounds() + +# add the 6 extraDof for velocity and acceleration (see *_path.py script) +fullBody.client.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.client.robot.setExtraConfigSpaceBounds([-tp.vMax,tp.vMax,-tp.vMax,tp.vMax,0,0,-tp.aMax,tp.aMax,-tp.aMax,tp.aMax,0,0]) +ps = tp.ProblemSolver( fullBody ) +ps.setParameter("Kinodynamic/velocityBound",tp.vMax) +ps.setParameter("Kinodynamic/accelerationBound",tp.aMax) +ps.setParameter("FullBody/frictionCoefficient",tp.mu) +#load the viewer +try : + v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = 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() + + +# load a reference configuration +q_ref = fullBody.referenceConfig[::]+[0]*6 +q_init = q_ref[::] +fullBody.setReferenceConfig(q_ref) +fullBody.setPostureWeights(fullBody.postureWeights[::]+[0]*6) +#fullBody.usePosturalTaskContactCreation(True) + +fullBody.setCurrentConfig (q_init) + +print "Generate limb DB ..." +tStart = time.time() +# generate databases : + +fullBody.loadAllLimbs("static","ReferenceConfiguration",nbSamples=100000) + + +tGenerate = time.time() - tStart +print "Done." +print "Databases generated in : "+str(tGenerate)+" s" + +#define initial and final configurations : +configSize = fullBody.getConfigSize() -fullBody.client.robot.getDimensionExtraConfigSpace() + +q_init[0:7] = tp.ps.configAtParam(pId,0)[0:7] # use this to get the correct orientation +q_goal = q_init[::]; q_goal[0:7] = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[0:7] +vel_init = tp.ps.configAtParam(pId,0)[tp.indexECS:tp.indexECS+3] +acc_init = tp.ps.configAtParam(pId,0)[tp.indexECS+3:tp.indexECS+6] +vel_goal = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[tp.indexECS:tp.indexECS+3] +acc_goal = [0,0,0] + +robTreshold = 5 +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = vel_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = vel_goal[::] +q_goal[configSize+3:configSize+6] = [0,0,0] + + + +fullBody.setStaticStability(True) + + +id_init = fullBody.generateStateInContact(q_init, [0,0,1]) +id_goal = fullBody.generateStateInContact(q_goal, [0,0,1]) + + +v(fullBody.getConfigAtState(id_init)) +fullBody.setStartStateId(id_init) +v(fullBody.getConfigAtState(id_goal)) +fullBody.setEndStateId(id_goal) + +print "Generate contact plan ..." +tStart = time.time() +configs = fullBody.interpolate(0.001,pathId=pId,robustnessTreshold = 1, filterStates = True,testReachability=True,quasiStatic=True) +tInterpolateConfigs = time.time() - tStart +print "Done." +print "Contact plan generated in : "+str(tInterpolateConfigs)+" s" +print "number of configs :", len(configs) +#raw_input("Press Enter to display the contact sequence ...") +#displayContactSequence(v,configs) + +if len(configs) < 2 : + cg_success = False + print "Error during contact generation." +else: + cg_success = True + print "Contact generation Done." +if abs(configs[-1][0] - tp.q_goal[0]) < 0.01 and abs(configs[-1][1]- tp.q_goal[1]) < 0.01 and (len(fullBody.getContactsVariations(len(configs)-2,len(configs)-1))==1): + print "Contact generation successful." + cg_reach_goal = True +else: + print "Contact generation failed to reach the goal." + cg_reach_goal = False + +f = open(statusFilename,"a") +f.write("cg_success: "+str(cg_success)+"\n") +f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n") +f.close() + +if (not cg_success): + import sys + sys.exit(1) + +#beginId = 2 + +# put back original bounds for wholebody methods +fullBody.resetJointsBounds() +#displayContactSequence(v,configs) diff --git a/script/scenarios/memmo/anymal_platform_random_path.py b/script/scenarios/memmo/anymal_platform_random_path.py new file mode 100644 index 0000000000000000000000000000000000000000..3cb613882ca8bac9ff6c38b62de4a25ebd9b1e31 --- /dev/null +++ b/script/scenarios/memmo/anymal_platform_random_path.py @@ -0,0 +1,148 @@ +from hpp.corbaserver.rbprm.anymal_abstract import Robot +from hpp.gepetto import Viewer +from hpp.corbaserver import ProblemSolver +from pinocchio import Quaternion +import numpy as np +import time +import math +statusFilename = "/res/infos.log" + + +vInit = 0.05# initial / final velocity to fix the direction +vGoal = 0.01 +vMax = 0.5# linear velocity bound for the root +aMax = 0.5# linear acceleration bound for the root +extraDof = 6 +mu=0.3# coefficient of friction +# Creating an instance of the helper class, and loading the robot +# Creating an instance of the helper class, and loading the robot +rbprmBuilder = Robot () +# Define bounds for the root : bounding box of the scenario +rootBounds = [0.4,3.6, 0.4, 2., 0.4, 0.5] +rbprmBuilder.setJointBounds ("root_joint", rootBounds) + +# 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([]) +for rom in rbprmBuilder.urdfNameRom : + rbprmBuilder.setAffordanceFilter(rom, ['Support']) + +# We also bound the rotations of the torso. (z, y, x) +rbprmBuilder.boundSO3([-3.14,3.14,-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) +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) + +# 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/plateforme_not_flat", "planning", vf, reduceSizes=[0.05,0,0]) +try : + v = vf.createViewer(displayArrows = True) +except Exception: + print "No viewer started !" + class FakeViewer(): + def __init__(self): + return + def __call__(self,q): + return + v = FakeViewer() + +#afftool.visualiseAffordances('Support', v, v.color.lightBrown) + +#v.addLandmark(v.sceneName,1) +q_init = rbprmBuilder.getCurrentConfig (); + +# Generate random init and goal position. +X_BOUNDS=[0.4,3.6] +Y_BOUNDS=[0.4,2.] +Z_VALUE = 0.465 + + +import random +random.seed() + +q_init[0:3] = [random.uniform(X_BOUNDS[0],X_BOUNDS[1]),random.uniform(Y_BOUNDS[0],Y_BOUNDS[1]),Z_VALUE] +q_goal=q_init[::] +for i in range(random.randint(0,1000)): + random.uniform(0.,1.) +q_goal[0:3] = [random.uniform(X_BOUNDS[0],X_BOUNDS[1]),random.uniform(Y_BOUNDS[0],Y_BOUNDS[1]),Z_VALUE] + + + +# compute the orientation such that q_init face q_goal : +# set final orientation to be along the circle : +vx = np.matrix([1,0,0]).T +v_init = np.matrix([q_goal[0]-q_init[0],q_goal[1]-q_init[1],0]).T +quat = Quaternion.FromTwoVectors(vx,v_init) +q_init[3:7] = quat.coeffs().T.tolist()[0] +q_goal[3:7] = q_init[3:7] + + + +print "initial root position : ",q_init +print "final root position : ",q_goal +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +# write problem in files : +f = open(statusFilename,"w") +f.write("q_init= "+str(q_init)+"\n") +f.write("q_goal= "+str(q_goal)+"\n") +f.close() + + +# Choosing RBPRM shooter and path validation methods. +ps.selectConfigurationShooter("RbprmShooter") +ps.selectPathValidation("RbprmPathValidation",0.05) +# Choosing kinodynamic methods : +#ps.selectSteeringMethod("RBPRMKinodynamic") +#ps.selectDistance("Kinodynamic") +#ps.selectPathPlanner("DynamicPlanner") + +# Solve the planning problem : +success = ps.client.problem.prepareSolveStepByStep() + +if not success: + print "planning failed." + import sys + sys.exit(1) + +ps.client.problem.finishSolveStepByStep() + + +try : + # display solution : + from hpp.gepetto import PathPlayer + pp = PathPlayer (v) + pp.dt=0.1 + pp.displayPath(0)#pp.displayVelocityPath(0) # + #v.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP") + pp.dt=0.01 + #pp(0) +except Exception: + pass + +# move the robot out of the view before computing the contacts +q_far = q_init[::] +q_far[2] = -2 +v(q_far) + diff --git a/script/scenarios/memmo/talos_circle_oriented_path.py b/script/scenarios/memmo/talos_circle_oriented_path.py index eb03e0b0dca77c488460c361897b050e8f776686..b01213ff311b9f4d38e1d59314e0a23839f99e3d 100644 --- a/script/scenarios/memmo/talos_circle_oriented_path.py +++ b/script/scenarios/memmo/talos_circle_oriented_path.py @@ -4,7 +4,7 @@ from hpp.corbaserver import ProblemSolver import numpy as np from pinocchio import Quaternion import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" vMax = 0.5# linear velocity bound for the root diff --git a/script/scenarios/memmo/talos_circle_path.py b/script/scenarios/memmo/talos_circle_path.py index 40256d4a4b9fcd10d795ff1e0ed60b5f6af6f1a3..d9bc5e191f3836334f3350580b543fc2e8263af7 100644 --- a/script/scenarios/memmo/talos_circle_path.py +++ b/script/scenarios/memmo/talos_circle_path.py @@ -3,7 +3,7 @@ from hpp.gepetto import Viewer from hpp.corbaserver import ProblemSolver import numpy as np import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" vMax = 0.5# linear velocity bound for the root diff --git a/script/scenarios/memmo/talos_moveEffector_flat.py b/script/scenarios/memmo/talos_moveEffector_flat.py index 2d7aaf1ed9a668c68a4007175880106273315761..e0675554d7af96b78ccd74ba812e9925f016fb47 100644 --- a/script/scenarios/memmo/talos_moveEffector_flat.py +++ b/script/scenarios/memmo/talos_moveEffector_flat.py @@ -6,7 +6,7 @@ from hpp.corbaserver import ProblemSolver import os import random import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" diff --git a/script/scenarios/memmo/talos_moveEffector_stairs_m10.py b/script/scenarios/memmo/talos_moveEffector_stairs_m10.py index e1c5348e2cd3ab10ad24a3cf2498936765b28825..22fe5e38cf43a75e01e32bb902554ac9ead79fd2 100644 --- a/script/scenarios/memmo/talos_moveEffector_stairs_m10.py +++ b/script/scenarios/memmo/talos_moveEffector_stairs_m10.py @@ -6,7 +6,7 @@ from hpp.corbaserver import ProblemSolver import os import random import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" diff --git a/script/scenarios/memmo/talos_moveEffector_stairs_m15.py b/script/scenarios/memmo/talos_moveEffector_stairs_m15.py index d6e0eac434b0132d23b377e613b47803c9722f41..a8ecf5032593be71ae447c71777b5773ce5fbadf 100644 --- a/script/scenarios/memmo/talos_moveEffector_stairs_m15.py +++ b/script/scenarios/memmo/talos_moveEffector_stairs_m15.py @@ -6,7 +6,7 @@ from hpp.corbaserver import ProblemSolver import os import random import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" diff --git a/script/scenarios/memmo/talos_moveEffector_stairs_p10.py b/script/scenarios/memmo/talos_moveEffector_stairs_p10.py index 6df22ff2e06038f4b595bd276bcdb6f7ab29847d..7a095c6032269257ff34527422843f6e3576b208 100644 --- a/script/scenarios/memmo/talos_moveEffector_stairs_p10.py +++ b/script/scenarios/memmo/talos_moveEffector_stairs_p10.py @@ -6,7 +6,7 @@ from hpp.corbaserver import ProblemSolver import os import random import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" diff --git a/script/scenarios/memmo/talos_moveEffector_stairs_p15.py b/script/scenarios/memmo/talos_moveEffector_stairs_p15.py index 1ffb355d9600f32b6aea3ff0f82c6abf54f62c63..ba98fc28e7646115427b6e863331f11e557c33ad 100644 --- a/script/scenarios/memmo/talos_moveEffector_stairs_p15.py +++ b/script/scenarios/memmo/talos_moveEffector_stairs_p15.py @@ -6,7 +6,7 @@ from hpp.corbaserver import ProblemSolver import os import random import time -statusFilename = "infos.log" +statusFilename = "/res/infos.log" diff --git a/script/scenarios/memmo/talos_platform.py b/script/scenarios/memmo/talos_platform.py new file mode 100644 index 0000000000000000000000000000000000000000..875ee14032d5a2e7ab7c31a032b216a10c9366fb --- /dev/null +++ b/script/scenarios/memmo/talos_platform.py @@ -0,0 +1,185 @@ +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_platform_path as tp + +pId = 0 +""" +print "Done." +import time +statusFilename = tp.statusFilename + +f = open(statusFilename,"a") +if tp.ps.numberPaths() > 0 : + print "Path planning OK." + f.write("Planning_success: True"+"\n") + f.close() +else : + print "Error during path planning" + f.write("Planning_success: False"+"\n") + f.close() + import sys + sys.exit(1) +""" + +fullBody = Robot () + +# Set the bounds for the root +fullBody.setJointBounds ("root_joint", tp.rootBounds) +fullBody.setConstrainedJointsBounds() + +# add the 6 extraDof for velocity and acceleration (see *_path.py script) +fullBody.client.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.client.robot.setExtraConfigSpaceBounds([-tp.vMax,tp.vMax,-tp.vMax,tp.vMax,0,0,-tp.aMax,tp.aMax,-tp.aMax,tp.aMax,0,0]) +ps = tp.ProblemSolver( fullBody ) +ps.setParameter("Kinodynamic/velocityBound",tp.vMax) +ps.setParameter("Kinodynamic/accelerationBound",tp.aMax) +#load the viewer +try : + v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = 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() + + +# load a reference configuration +q_ref = fullBody.referenceConfig[::]+[0]*6 +#q_ref = fullBody.referenceConfig_legsApart[::]+[0]*6 +q_init = q_ref[::] +fullBody.setReferenceConfig(q_ref) + +""" +if abs(tp.q_goal[1]) <= abs(tp.q_goal[0]) : + fullBody.setPostureWeights(fullBody.postureWeights[::]+[0]*6) + heuristicR = "fixedStep08" + heuristicL = "fixedStep08" + print "Use weight for straight walk" + fullBody.usePosturalTaskContactCreation(True) +else : + fullBody.setPostureWeights(fullBody.postureWeights_straff[::]+[0]*6) + print "Use weight for straff walk" + if tp.q_goal[1] < 0 : + print "start with right leg" + heuristicL = "static" + heuristicR = "fixedStep06" + else: + print "start with left leg" + heuristicR = "static" + heuristicL = "fixedStep06" +""" + +fullBody.setCurrentConfig (q_init) + +print "Generate limb DB ..." +tStart = time.time() +# 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.addLimb(fullBody.lLegId,fullBody.lleg,fullBody.lfoot,fullBody.lLegOffset,fullBody.rLegNormal, fullBody.lLegx, fullBody.lLegy, nbSamples, "fixedStep06", 0.01,kinematicConstraintsPath=fullBody.lLegKinematicConstraints,kinematicConstraintsMin = 0.85) +fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True) + + +tGenerate = time.time() - tStart +print "Done." +print "Databases generated in : "+str(tGenerate)+" s" + +#define initial and final configurations : +configSize = fullBody.getConfigSize() -fullBody.client.robot.getDimensionExtraConfigSpace() + +q_init[0:7] = tp.ps.configAtParam(pId,0)[0:7] # use this to get the correct orientation +q_goal = q_init[::]; q_goal[0:7] = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[0:7] +vel_init = tp.ps.configAtParam(pId,0)[tp.indexECS:tp.indexECS+3] +acc_init = tp.ps.configAtParam(pId,0)[tp.indexECS+3:tp.indexECS+6] +vel_goal = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[tp.indexECS:tp.indexECS+3] +acc_goal = [0,0,0] + +robTreshold = 3 +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = vel_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = vel_goal[::] +q_goal[configSize+3:configSize+6] = [0,0,0] + + +q_init[2] = q_ref[2] +q_goal[2] = q_ref[2] + + +fullBody.setStaticStability(True) +fullBody.setCurrentConfig (q_init) +v(q_init) + +fullBody.setCurrentConfig (q_goal) +v(q_goal) + +v.addLandmark('talos/base_link',0.3) +v(q_init) +#fullBody.setReferenceConfig(fullBody.referenceConfig_legsApart[::]+[0]*6) + + +# specify the full body configurations as start and goal state of the problem + +if q_goal[1] < 0: # goal on the right side of the circle, start motion with right leg first + fullBody.setStartState(q_init,[fullBody.rLegId,fullBody.lLegId]) + fullBody.setEndState(q_goal,[fullBody.rLegId,fullBody.lLegId]) +else : + fullBody.setStartState(q_init,[fullBody.lLegId,fullBody.rLegId]) + fullBody.setEndState(q_goal,[fullBody.lLegId,fullBody.rLegId]) + +print "Generate contact plan ..." +tStart = time.time() +configs = fullBody.interpolate(0.005,pathId=pId,robustnessTreshold = 3, filterStates = True,quasiStatic=True) +tInterpolateConfigs = time.time() - tStart +print "Done." +print "Contact plan generated in : "+str(tInterpolateConfigs)+" s" +print "number of configs :", len(configs) +#raw_input("Press Enter to display the contact sequence ...") +#displayContactSequence(v,configs) + + +if len(configs) < 2 : + cg_success = False + print "Error during contact generation." +else: + cg_success = True + print "Contact generation Done." +if abs(configs[-1][0] - tp.q_goal[0]) < 0.01 and abs(configs[-1][1]- tp.q_goal[1]) < 0.01 and (len(fullBody.getContactsVariations(len(configs)-2,len(configs)-1))==1): + print "Contact generation successful." + cg_reach_goal = True +else: + print "Contact generation failed to reach the goal." + cg_reach_goal = False +if len(configs) > 5 : + cg_too_many_states = True + cg_success = False + print "Discarded contact sequence because it was too long." +else: + cg_too_many_states = False + +f = open(statusFilename,"a") +f.write("cg_success: "+str(cg_success)+"\n") +f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n") +f.write("cg_too_many_states: "+str(cg_too_many_states)+"\n") +f.close() + +if (not cg_success) or cg_too_many_states or (not cg_reach_goal): + import sys + sys.exit(1) + +# put back original bounds for wholebody methods +fullBody.setJointBounds('leg_left_6_joint',joint6L_bounds_prev) +fullBody.setJointBounds('leg_left_2_joint',joint2L_bounds_prev) +fullBody.setJointBounds('leg_right_6_joint',joint6R_bounds_prev) +fullBody.setJointBounds('leg_right_2_joint',joint2R_bounds_prev) + diff --git a/script/scenarios/memmo/talos_platform_path.py b/script/scenarios/memmo/talos_platform_path.py new file mode 100644 index 0000000000000000000000000000000000000000..bef10cb240fe05ed297b09b1ca6d55ed7e546696 --- /dev/null +++ b/script/scenarios/memmo/talos_platform_path.py @@ -0,0 +1,125 @@ +from hpp.corbaserver.rbprm.talos_abstract import Robot +from hpp.gepetto import Viewer +from hpp.corbaserver import ProblemSolver +import numpy as np +import time +statusFilename = "infos.log" + + +vMax = 0.5# linear velocity bound for the root +aMax = 0.5# 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 +# Creating an instance of the helper class, and loading the robot +rbprmBuilder = Robot () +# Define bounds for the root : bounding box of the scenario +rootBounds = [0.2,3.9, 0.2, 2.2, 0.95, 1.05] +rbprmBuilder.setJointBounds ("root_joint", rootBounds) + +# 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([-1.7,1.7,-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) +ps.setParameter("DynamicPlanner/sizeFootX",0.2) +ps.setParameter("DynamicPlanner/sizeFootY",0.12) +ps.setParameter("DynamicPlanner/friction",0.5) +# sample only configuration with null velocity and acceleration : +ps.setParameter("ConfigurationShooter/sampleExtraDOF",False) + +# 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/plateforme_not_flat", "planning", vf, reduceSizes=[0.13,0,0]) +try : + v = vf.createViewer(displayArrows = True) +except Exception: + print "No viewer started !" + class FakeViewer(): + def __init__(self): + return + def __call__(self,q): + return + v = FakeViewer() + +#afftool.visualiseAffordances('Support', v, v.color.lightBrown) + +v.addLandmark(v.sceneName,1) +q_init = rbprmBuilder.getCurrentConfig (); +q_init[0:3] = [0.3,1.15,0.98] +q_init[3:7] = [0,0,0,1] + +# sample random position on a circle of radius 2m +""" +radius = 0.3 +import random +random.seed() +alpha = random.uniform(0.,2.*np.pi) +print "Test on a circle, alpha = ",alpha +q_goal = q_init[::] +q_goal [0:3] = [radius*np.sin(alpha), -radius*np.cos(alpha), 1.] +""" +q_goal = q_init[::] +q_goal [0:2] = [3.3,2.2] + +print "initial root position : ",q_init[0:3] +print "final root position : ",q_goal[0:3] +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +# write problem in files : +""" +f = open(statusFilename,"w") +f.write("q_init= "+str(q_init)+"\n") +f.write("q_goal= "+str(q_goal)+"\n") +f.close() +""" + +# Choosing RBPRM shooter and path validation methods. +ps.selectConfigurationShooter("RbprmShooter") +ps.selectPathValidation("RbprmPathValidation",0.05) +# Choosing kinodynamic methods : +ps.selectSteeringMethod("RBPRMKinodynamic") +ps.selectDistance("Kinodynamic") +ps.selectPathPlanner("DynamicPlanner") + +# Solve the planning problem : +t = ps.solve () +print "Guide planning time : ",t + +try : + # 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") + pp.dt=0.01 + #pp(0) +except Exception: + pass + +# move the robot out of the view before computing the contacts +q_far = q_init[::] +q_far[2] = -2 +v(q_far) + diff --git a/script/scenarios/memmo/talos_platform_random.py b/script/scenarios/memmo/talos_platform_random.py new file mode 100644 index 0000000000000000000000000000000000000000..66ba0abe71b70d2e11ee49fcc94418589f869324 --- /dev/null +++ b/script/scenarios/memmo/talos_platform_random.py @@ -0,0 +1,162 @@ +from hpp.corbaserver.rbprm.talos import Robot +from hpp.gepetto import Viewer +from tools.display_tools import * +import time +print "Plan guide trajectory ..." +import scenarios.memmo.talos_platform_random_path as tp +#Robot.urdfSuffix += "_safeFeet" +statusFilename = tp.statusFilename +pId = 0 +f = open(statusFilename,"a") +if tp.ps.numberPaths() > 0 : + print "Path planning OK." + f.write("Planning_success: True"+"\n") + f.close() +else : + print "Error during path planning" + f.write("Planning_success: False"+"\n") + f.close() + import sys + sys.exit(1) + +fullBody = Robot () + +# Set the bounds for the root +rootBounds = tp.rootBounds[::] +rootBounds[-2] -= 0.2 +rootBounds[0] -= 0.2 +rootBounds[1] += 0.2 +rootBounds[2] -= 0.2 +rootBounds[3] += 0.2 +fullBody.setJointBounds ("root_joint", rootBounds) +fullBody.setConstrainedJointsBounds() + +# add the 6 extraDof for velocity and acceleration (see *_path.py script) +fullBody.client.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.client.robot.setExtraConfigSpaceBounds([-tp.vMax,tp.vMax,-tp.vMax,tp.vMax,0,0,-tp.aMax,tp.aMax,-tp.aMax,tp.aMax,0,0]) +ps = tp.ProblemSolver( fullBody ) +ps.setParameter("Kinodynamic/velocityBound",tp.vMax) +ps.setParameter("Kinodynamic/accelerationBound",tp.aMax) +ps.setParameter("FullBody/frictionCoefficient",tp.mu) +#load the viewer +try : + v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = 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() + + +# load a reference configuration +#q_ref = fullBody.referenceConfig[::]+[0]*6 +q_ref = fullBody.referenceConfig_legsApart[::]+[0]*6 +q_init = q_ref[::] +fullBody.setReferenceConfig(q_ref) +fullBody.setPostureWeights(fullBody.postureWeights[::]+[0]*6) +fullBody.usePosturalTaskContactCreation(True) + +fullBody.setCurrentConfig (q_init) + +print "Generate limb DB ..." +tStart = time.time() +# generate databases : + +nbSamples = 100000 +fullBody.addLimb(fullBody.rLegId,fullBody.rleg,fullBody.rfoot,fullBody.rLegOffset,fullBody.rLegNormal, fullBody.rLegx, fullBody.rLegy, nbSamples, "fixedStep08", 0.01,kinematicConstraintsPath=fullBody.rLegKinematicConstraints,kinematicConstraintsMin = 0.8) +#fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True) +fullBody.addLimb(fullBody.lLegId,fullBody.lleg,fullBody.lfoot,fullBody.lLegOffset,fullBody.rLegNormal, fullBody.lLegx, fullBody.lLegy, nbSamples, "fixedStep08", 0.01,kinematicConstraintsPath=fullBody.lLegKinematicConstraints,kinematicConstraintsMin = 0.8) +#fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True) + + +tGenerate = time.time() - tStart +print "Done." +print "Databases generated in : "+str(tGenerate)+" s" + +#define initial and final configurations : +configSize = fullBody.getConfigSize() -fullBody.client.robot.getDimensionExtraConfigSpace() + +q_init[0:7] = tp.ps.configAtParam(pId,0)[0:7] # use this to get the correct orientation +q_goal = q_init[::]; q_goal[0:7] = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[0:7] +vel_init = tp.ps.configAtParam(pId,0)[tp.indexECS:tp.indexECS+3] +acc_init = tp.ps.configAtParam(pId,0)[tp.indexECS+3:tp.indexECS+6] +vel_goal = tp.ps.configAtParam(pId,tp.ps.pathLength(pId))[tp.indexECS:tp.indexECS+3] +acc_goal = [0,0,0] + +robTreshold = 3 +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = vel_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = vel_goal[::] +q_goal[configSize+3:configSize+6] = [0,0,0] + + + +fullBody.setStaticStability(True) +#v.addLandmark('talos/base_link',0.3) + +# FOR EASY SCENARIOS ? +q_init[2]=q_ref[2] +q_goal[2]=q_ref[2] + + +# define init gait according to the direction of motion, try to move first the leg on the outside of the turn : +if q_goal[0] > q_init[0] : #go toward x positif + if q_goal[1] > q_init[1]: # turn left + gait = [fullBody.rLegId,fullBody.lLegId] + else : # turn right + gait = [fullBody.lLegId,fullBody.rLegId] +else : # go toward x negatif + if q_goal[1] > q_init[1]: # turn right + gait = [fullBody.lLegId,fullBody.rLegId] + else : # turn left + gait = [fullBody.rLegId,fullBody.lLegId] + +v(q_init) +fullBody.setStartState(q_init,gait) +v(q_goal) +fullBody.setEndState(q_goal,gait) + +print "Generate contact plan ..." +tStart = time.time() +v(q_init) +configs = fullBody.interpolate(0.005,pathId=pId,robustnessTreshold = 1, filterStates = True,testReachability=True,quasiStatic=True) +tInterpolateConfigs = time.time() - tStart +print "Done." +print "Contact plan generated in : "+str(tInterpolateConfigs)+" s" +print "number of configs :", len(configs) +#raw_input("Press Enter to display the contact sequence ...") +#displayContactSequence(v,configs) + +if len(configs) < 2 : + cg_success = False + print "Error during contact generation." +else: + cg_success = True + print "Contact generation Done." +if abs(configs[-1][0] - tp.q_goal[0]) < 0.01 and abs(configs[-1][1]- tp.q_goal[1]) < 0.01 and (len(fullBody.getContactsVariations(len(configs)-2,len(configs)-1))==1): + print "Contact generation successful." + cg_reach_goal = True +else: + print "Contact generation failed to reach the goal." + cg_reach_goal = False + +f = open(statusFilename,"a") +f.write("cg_success: "+str(cg_success)+"\n") +f.write("cg_reach_goal: "+str(cg_reach_goal)+"\n") +f.close() + +if (not cg_success): + import sys + sys.exit(1) + + + +# put back original bounds for wholebody methods +fullBody.resetJointsBounds() +#displayContactSequence(v,configs) diff --git a/script/scenarios/memmo/talos_platform_random_path.py b/script/scenarios/memmo/talos_platform_random_path.py new file mode 100644 index 0000000000000000000000000000000000000000..7f679b3d38b865e68052ac574031d8ed8af87025 --- /dev/null +++ b/script/scenarios/memmo/talos_platform_random_path.py @@ -0,0 +1,157 @@ +from hpp.corbaserver.rbprm.talos_abstract import Robot +from hpp.gepetto import Viewer +from hpp.corbaserver import ProblemSolver +from pinocchio import Quaternion +import numpy as np +import time +import math +statusFilename = "/res/infos.log" + + +vInit = 0.05# initial / final velocity to fix the direction +vGoal = 0.01 +vMax = 0.5# linear velocity bound for the root +aMax = 0.5# linear acceleration bound for the root +extraDof = 6 +mu=0.3# coefficient of friction +# Creating an instance of the helper class, and loading the robot +# Creating an instance of the helper class, and loading the robot +rbprmBuilder = Robot () +# Define bounds for the root : bounding box of the scenario +rootBounds = [0.1,4., 0.2, 2.2, 0.95, 1.05] +rbprmBuilder.setJointBounds ("root_joint", rootBounds) + +# 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([-3.14,3.14,-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) +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) + +# 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/plateforme_not_flat", "planning", vf, reduceSizes=[0.1,0,0]) +try : + v = vf.createViewer(displayArrows = True) +except Exception: + print "No viewer started !" + class FakeViewer(): + def __init__(self): + return + def __call__(self,q): + return + v = FakeViewer() + +#afftool.visualiseAffordances('Support', v, v.color.lightBrown) + +#v.addLandmark(v.sceneName,1) +q_init = rbprmBuilder.getCurrentConfig (); + +# Generate random init and goal position. +# these position will be on the flat part of the environment, with an orientation such that they can be connected by a straight line, and an angle between +- 25 degree from the x axis +Y_BOUNDS=[0.3,2.1] +Z_VALUE = 0.98 +MAX_ANGLE = 0.4363323129985824 # 25 degree + +import random +random.seed() + +# select randomly the initial and final plateform, they cannot be the same +# end plateform is always after the init plateform on the x axis +init_plateform_id = random.randint(0,3) +end_plateform_id = random.randint(init_plateform_id+1,4) +#if end_plateform_id >= init_plateform_id: +# end_plateform_id+=1 + +# set x position from the plateform choosen : +x_init = 0.16 + 0.925*init_plateform_id +x_goal = 0.16 + 0.925*end_plateform_id + +# uniformly sample y position +y_init = random.uniform(Y_BOUNDS[0],Y_BOUNDS[1]) +q_init[0:3] = [x_init,y_init, Z_VALUE] + +# y_goal must be random inside Y_BOUNDS but such that the line between q_init and q_goal is between +- MAX_ANGLE radian from the x axis +y_bound_goal = Y_BOUNDS[::] +y_angle_max = math.sin(MAX_ANGLE)*abs(x_init-x_goal) + y_init +y_angle_min = math.sin(-MAX_ANGLE)*abs(x_init-x_goal) + y_init +y_bound_goal[0] = max(y_angle_min,y_bound_goal[0]) +y_bound_goal[1] = min(y_angle_max,y_bound_goal[1]) +y_goal = random.uniform(y_bound_goal[0],y_bound_goal[1]) + + + +# compute the orientation such that q_init face q_goal : +# set final orientation to be along the circle : +vx = np.matrix([1,0,0]).T +v_init = np.matrix([x_goal-x_init,y_goal-y_init,0]).T +quat = Quaternion.FromTwoVectors(vx,v_init) +q_init[3:7] = quat.coeffs().T.tolist()[0] + +q_goal=q_init[::] +q_goal[0:2] = [x_goal,y_goal] + +print "initial root position : ",q_init +print "final root position : ",q_goal +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +# write problem in files : +f = open(statusFilename,"w") +f.write("q_init= "+str(q_init)+"\n") +f.write("q_goal= "+str(q_goal)+"\n") +f.close() + + +# Choosing RBPRM shooter and path validation methods. +ps.selectConfigurationShooter("RbprmShooter") +ps.selectPathValidation("RbprmPathValidation",0.05) +# Choosing kinodynamic methods : +#ps.selectSteeringMethod("RBPRMKinodynamic") +#ps.selectDistance("Kinodynamic") +#ps.selectPathPlanner("DynamicPlanner") + +# Solve the planning problem : +t = ps.solve () +print "Guide planning time : ",t + +try : + # display solution : + from hpp.gepetto import PathPlayer + pp = PathPlayer (v) + pp.dt=0.1 + pp.displayPath(0)#pp.displayVelocityPath(0) # + #v.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP") + pp.dt=0.01 + #pp(0) +except Exception: + pass + +# move the robot out of the view before computing the contacts +q_far = q_init[::] +q_far[2] = -2 +v(q_far) + diff --git a/src/rbprmbuilder.impl.cc b/src/rbprmbuilder.impl.cc index 1606f049aef452515d5be3857475b339d773336f..1eaa00e2693c9a1b89b4a8b4894c0d6bad048c9e 100644 --- a/src/rbprmbuilder.impl.cc +++ b/src/rbprmbuilder.impl.cc @@ -170,13 +170,9 @@ namespace hpp { fullBodyMap_.selected_ = name; if(problemSolver()){ if(problemSolver()->problem()){ - try { - double mu = problemSolver()->problem()->getParameter ("friction").floatValue(); - fullBody()->setFriction(mu); - hppDout(notice,"fullbody : mu define in python : "<<fullBody()->getFriction()); - } catch (const std::exception& e) { - hppDout(notice,"fullbody : mu not defined, take : "<<fullBody()->getFriction()<<" as default."); - } + double mu = problemSolver()->problem()->getParameter ("FullBody/frictionCoefficient").floatValue(); + fullBody()->setFriction(mu); + hppDout(notice,"fullbody : friction coefficient used : "<<fullBody()->getFriction()); }else{ hppDout(warning,"No instance of problem while initializing fullBody"); } @@ -3483,6 +3479,13 @@ namespace hpp { return new hpp::floatSeq(); } + HPP_START_PARAMETER_DECLARATION(FullBody) + Problem::declareParameter(core::ParameterDescription (core::Parameter::FLOAT, + "FullBody/frictionCoefficient", + "The coefficient of friction used between the robot and the environment.", + core::Parameter(0.5))); + HPP_END_PARAMETER_DECLARATION(FullBody) + } // namespace impl } // namespace rbprm