diff --git a/script/dynamic/downSlope_hyq_interpKino.py b/script/dynamic/downSlope_hyq_interpKino.py new file mode 100644 index 0000000000000000000000000000000000000000..c269ad5eae9df4327e9595842f038d6f65cee254 --- /dev/null +++ b/script/dynamic/downSlope_hyq_interpKino.py @@ -0,0 +1,125 @@ +#Importing helper class for RBPRM +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver +from hpp.gepetto import Viewer + +#calling script darpa_hyq_path to compute root path +import downSlope_hyq_pathKino as tp + +from os import environ +ins_dir = environ['DEVEL_DIR'] +db_dir = ins_dir+"/install/share/hyq-rbprm/database/hyq_" + +pathId = tp.ps.numberPaths()-1 + +packageName = "hyq_description" +meshPackageName = "hyq_description" +rootJointType = "freeflyer" + +# Information to retrieve urdf and srdf files. +urdfName = "hyq" +urdfSuffix = "" +srdfSuffix = "" + +# This time we load the full body model of HyQ +fullBody = FullBody () +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +fullBody.client.basic.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.setJointBounds ("base_joint_xyz", [-1.25,5, 0, 2, 0.3, 1.8]) + +# Setting a number of sample configurations used +nbSamples = 20000 +dynamic=True + +ps = tp.ProblemSolver(fullBody) +ps.client.problem.setParameter("aMax",tp.aMax) +ps.client.problem.setParameter("vMax",tp.vMax) +r = tp.Viewer (ps,viewerClient=tp.r.client) + +rootName = 'base_joint_xyz' + + +def addLimbDb(limbId, heuristicName, loadValues = True, disableEffectorCollision = False): + fullBody.addLimbDatabase(str(db_dir+limbId+'.db'), limbId, heuristicName,loadValues, disableEffectorCollision) + +rLegId = 'rfleg' +lLegId = 'lhleg' +rarmId = 'rhleg' +larmId = 'lfleg' + +addLimbDb(rLegId, "EFORT_Normal") +addLimbDb(lLegId, "EFORT_Normal") +addLimbDb(rarmId, "EFORT_Normal") +addLimbDb(larmId, "EFORT_Normal") + +q_0 = fullBody.getCurrentConfig(); +q_init = fullBody.getCurrentConfig(); q_init[0:7] = tp.ps.configAtParam(0,0.01)[0:7] # use this to get the correct orientation +q_goal = fullBody.getCurrentConfig(); q_goal[0:7] = tp.ps.configAtParam(pathId,tp.ps.pathLength(pathId))[0:7] +dir_init = tp.ps.configAtParam(pathId,0.01)[7:10] +acc_init = tp.ps.configAtParam(pathId,0.01)[10:13] +dir_goal = tp.ps.configAtParam(pathId,tp.ps.pathLength(pathId))[7:10] +acc_goal = tp.ps.configAtParam(pathId,tp.ps.pathLength(pathId))[10:13] +configSize = fullBody.getConfigSize() -fullBody.client.basic.robot.getDimensionExtraConfigSpace() + +fullBody.setStaticStability(False) +# Randomly generating a contact configuration at q_init +fullBody.setCurrentConfig (q_init) +q_init = fullBody.generateContacts(q_init,dir_init,acc_init) + +# Randomly generating a contact configuration at q_end +fullBody.setCurrentConfig (q_goal) +q_goal = fullBody.generateContacts(q_goal, dir_goal,acc_goal) + +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = dir_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = dir_goal[::] +q_goal[configSize+3:configSize+6] = acc_goal[::] +# specifying the full body configurations as start and goal state of the problem +fullBody.setStartState(q_init,[larmId,rLegId,rarmId,lLegId]) +fullBody.setEndState(q_goal,[larmId,rLegId,rarmId,lLegId]) + + +r(q_init) +# computing the contact sequence + +configs = fullBody.interpolate(0.08,pathId=pathId,robustnessTreshold = 2, filterStates = True) + + +print "number of configs =", len(configs) +r(configs[-1]) + +from hpp.gepetto import PathPlayer +pp = PathPlayer (fullBody.client.basic, r) + +from fullBodyPlayer import Player +player = Player(fullBody,pp,tp,configs,draw=True,optim_effector=False,use_velocity=dynamic,pathId = pathId) + +#player.displayContactPlan() + +r(configs[15]) +player.interpolate(15,60) + +#player.play() + + + +""" + +camera = [0.5681925415992737, + -6.707448482513428, + 2.5206544399261475, + 0.8217507600784302, + 0.5693002343177795, + 0.020600343123078346, + 0.01408931240439415] +r.client.gui.setCameraTransform(0,camera) + +""" + + + + + + diff --git a/script/dynamic/downSlope_hyq_interpKino2.py b/script/dynamic/downSlope_hyq_interpKino2.py new file mode 100644 index 0000000000000000000000000000000000000000..a885dcac78b3aa09bfe7cbd069356ca0f2f664a1 --- /dev/null +++ b/script/dynamic/downSlope_hyq_interpKino2.py @@ -0,0 +1,125 @@ +#Importing helper class for RBPRM +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver +from hpp.gepetto import Viewer + +#calling script darpa_hyq_path to compute root path +import downSlope_hyq_pathKino2 as tp + +from os import environ +ins_dir = environ['DEVEL_DIR'] +db_dir = ins_dir+"/install/share/hyq-rbprm/database/hyq_" + +pathId = tp.ps.numberPaths()-1 + +packageName = "hyq_description" +meshPackageName = "hyq_description" +rootJointType = "freeflyer" + +# Information to retrieve urdf and srdf files. +urdfName = "hyq" +urdfSuffix = "" +srdfSuffix = "" + +# This time we load the full body model of HyQ +fullBody = FullBody () +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +fullBody.client.basic.robot.setDimensionExtraConfigSpace(tp.extraDof) +fullBody.setJointBounds ("base_joint_xyz", [-1.25,5, 0, 2, 0.3, 1.8]) + +# Setting a number of sample configurations used +nbSamples = 20000 +dynamic=True + +ps = tp.ProblemSolver(fullBody) +ps.client.problem.setParameter("aMax",tp.aMax) +ps.client.problem.setParameter("vMax",tp.vMax) +r = tp.Viewer (ps,viewerClient=tp.r.client) + +rootName = 'base_joint_xyz' + + +def addLimbDb(limbId, heuristicName, loadValues = True, disableEffectorCollision = False): + fullBody.addLimbDatabase(str(db_dir+limbId+'.db'), limbId, heuristicName,loadValues, disableEffectorCollision) + +rLegId = 'rfleg' +lLegId = 'lhleg' +rarmId = 'rhleg' +larmId = 'lfleg' + +addLimbDb(rLegId, "EFORT_Normal") +addLimbDb(lLegId, "EFORT_Normal") +addLimbDb(rarmId, "EFORT_Normal") +addLimbDb(larmId, "EFORT_Normal") + +q_0 = fullBody.getCurrentConfig(); +q_init = fullBody.getCurrentConfig(); q_init[0:7] = tp.ps.configAtParam(0,0.01)[0:7] # use this to get the correct orientation +q_goal = fullBody.getCurrentConfig(); q_goal[0:7] = tp.ps.configAtParam(pathId,tp.ps.pathLength(pathId))[0:7] +dir_init = tp.ps.configAtParam(pathId,0.01)[7:10] +acc_init = tp.ps.configAtParam(pathId,0.01)[10:13] +dir_goal = tp.ps.configAtParam(pathId,tp.ps.pathLength(pathId)-0.01)[7:10] +acc_goal = tp.ps.configAtParam(pathId,tp.ps.pathLength(pathId)-0.01)[10:13] +configSize = fullBody.getConfigSize() -fullBody.client.basic.robot.getDimensionExtraConfigSpace() + +fullBody.setStaticStability(False) +# Randomly generating a contact configuration at q_init +fullBody.setCurrentConfig (q_init) +q_init = fullBody.generateContacts(q_init,dir_init,acc_init) + +# Randomly generating a contact configuration at q_end +fullBody.setCurrentConfig (q_goal) +q_goal = fullBody.generateContacts(q_goal, dir_goal,acc_goal) + +# copy extraconfig for start and init configurations +q_init[configSize:configSize+3] = dir_init[::] +q_init[configSize+3:configSize+6] = acc_init[::] +q_goal[configSize:configSize+3] = dir_goal[::] +q_goal[configSize+3:configSize+6] = acc_goal[::] +# specifying the full body configurations as start and goal state of the problem +fullBody.setStartState(q_init,[larmId,rLegId,rarmId,lLegId]) +fullBody.setEndState(q_goal,[larmId,rLegId,rarmId,lLegId]) + + +r(q_init) +# computing the contact sequence + +configs = fullBody.interpolate(0.08,pathId=pathId,robustnessTreshold = 0, filterStates = True) + + +print "number of configs =", len(configs) +r(configs[-1]) + +from hpp.gepetto import PathPlayer +pp = PathPlayer (fullBody.client.basic, r) + +from fullBodyPlayer import Player +player = Player(fullBody,pp,tp,configs,draw=True,optim_effector=False,use_velocity=dynamic,pathId = pathId) + +player.displayContactPlan() + +r(configs[15]) +player.interpolate(15,60) + +#player.play() + + + +""" + +camera = [0.5681925415992737, + -6.707448482513428, + 2.5206544399261475, + 0.8217507600784302, + 0.5693002343177795, + 0.020600343123078346, + 0.01408931240439415] +r.client.gui.setCameraTransform(0,camera) + +""" + + + + + + diff --git a/script/dynamic/downSlope_hyq_pathKino.py b/script/dynamic/downSlope_hyq_pathKino.py index 99e85a4704a3903ab4c189f8b119f9f6841c52b3..d68d5a23268b81317d49a36bbf5e654e43c327f5 100644 --- a/script/dynamic/downSlope_hyq_pathKino.py +++ b/script/dynamic/downSlope_hyq_pathKino.py @@ -21,7 +21,7 @@ extraDof = 6 rbprmBuilder = Builder () rbprmBuilder.loadModel(urdfName, urdfNameRom, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) #rbprmBuilder.setJointBounds ("base_joint_xyz", [-1.25,2, -0.5, 5.5, 0.6, 1.8]) -rbprmBuilder.setJointBounds ("base_joint_xyz", [-1.25,5, 0, 2, 0.3, 1.8]) +rbprmBuilder.setJointBounds ("base_joint_xyz", [-1.25,5, 0, 2, 0.45, 1.8]) # The following lines set constraint on the valid configurations: # a configuration is valid only if all limbs can create a contact ... rbprmBuilder.setFilter(['hyq_rhleg_rom', 'hyq_lfleg_rom', 'hyq_rfleg_rom','hyq_lhleg_rom']) @@ -130,7 +130,7 @@ pp.speed=0.3 #display path with post-optimisation -ps.client.problem.extractPath(0,0,2.6) +ps.client.problem.extractPath(0,0,1.95) r.client.gui.removeFromGroup("path_0_root",r.sceneName) pp.displayVelocityPath(1) #pp (1) diff --git a/script/dynamic/downSlope_hyq_pathKino2.py b/script/dynamic/downSlope_hyq_pathKino2.py new file mode 100644 index 0000000000000000000000000000000000000000..7268ef1c4b9f500a9ea132a0ab6250e9f160381a --- /dev/null +++ b/script/dynamic/downSlope_hyq_pathKino2.py @@ -0,0 +1,177 @@ +## Importing helper class for setting up a reachability planning problem +from hpp.corbaserver.rbprm.rbprmbuilder import Builder + +# Importing Gepetto viewer helper class +from hpp.gepetto import Viewer +import time + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +# URDF file describing the trunk of the robot HyQ +urdfName = 'hyq_trunk' +# URDF files describing the reachable workspace of each limb of HyQ +urdfNameRom = ['hyq_lhleg_rom','hyq_lfleg_rom','hyq_rfleg_rom','hyq_rhleg_rom'] +urdfSuffix = "" +srdfSuffix = "" +vMax = 4; +aMax = 5; +extraDof = 6 +# Creating an instance of the helper class, and loading the robot +rbprmBuilder = Builder () +rbprmBuilder.loadModel(urdfName, urdfNameRom, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +#rbprmBuilder.setJointBounds ("base_joint_xyz", [-1.25,2, -0.5, 5.5, 0.6, 1.8]) +rbprmBuilder.setJointBounds ("base_joint_xyz", [-1.25,5, 0, 2, 0.45, 1.8]) +# The following lines set constraint on the valid configurations: +# a configuration is valid only if all limbs can create a contact ... +rbprmBuilder.setFilter(['hyq_rhleg_rom', 'hyq_lfleg_rom', 'hyq_rfleg_rom','hyq_lhleg_rom']) +rbprmBuilder.setAffordanceFilter('hyq_rhleg_rom', ['Support']) +rbprmBuilder.setAffordanceFilter('hyq_rfleg_rom', ['Support',]) +rbprmBuilder.setAffordanceFilter('hyq_lhleg_rom', ['Support']) +rbprmBuilder.setAffordanceFilter('hyq_lfleg_rom', ['Support',]) +# We also bound the rotations of the torso. (z, y, x) +rbprmBuilder.boundSO3([-0.1,0.1,-0.65,0.65,-0.2,0.2]) +rbprmBuilder.client.basic.robot.setDimensionExtraConfigSpace(extraDof) +rbprmBuilder.client.basic.robot.setExtraConfigSpaceBounds([-vMax,vMax,-1,1,-2,2,0,0,0,0,0,0]) + +# Creating an instance of HPP problem solver and the viewer +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver +ps = ProblemSolver( rbprmBuilder ) +ps.client.problem.setParameter("aMax",aMax) +ps.client.problem.setParameter("vMax",vMax) +r = Viewer (ps) + +from hpp.corbaserver.affordance.affordance import AffordanceTool +afftool = AffordanceTool () +afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005]) +afftool.loadObstacleModel (packageName, "downSlope", "planning", r) +#r.loadObstacleModel (packageName, "ground", "planning") +afftool.visualiseAffordances('Support', r, [0.25, 0.5, 0.5]) +r.addLandmark(r.sceneName,1) + +# Setting initial and goal configurations +q_init = rbprmBuilder.getCurrentConfig (); +q_init[3:7] = [0.95371695,0,0.30070580,0] +q_init [0:3] = [-1.25, 1, 1.65]; r (q_init) +#q_init[3:7] = [0.7071,0,0,0.7071] +#q_init [0:3] = [1, 1, 0.65] + +rbprmBuilder.setCurrentConfig (q_init) +q_goal = q_init [::] + +#q_goal[3:7] = [1,0,0,0] +#q_goal [0:3] = [2, 1, 0.60]; r(q_goal) +q_goal[3:7] = [0.95371695,0,0.30070580,0] +q_goal[7:10] = [3,0,-2] +q_goal [0:3] = [0, 1, 0.8]; r(q_goal) + +r (q_goal) +#~ q_goal [0:3] = [-1.5, 0, 0.63]; r (q_goal) + +# Choosing a path optimizer +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) +# Choosing RBPRM shooter and path validation methods. +ps.client.problem.selectConFigurationShooter("RbprmShooter") +ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) +# Choosing kinodynamic methods : +ps.selectSteeringMethod("RBPRMKinodynamic") +ps.selectDistance("KinodynamicDistance") +ps.selectPathPlanner("DynamicPlanner") + +#solve the problem : +r(q_init) + +ps.client.problem.prepareSolveStepByStep() + +ps.client.problem.finishSolveStepByStep() + +q_far = q_init[::] +q_far[2] = -3 +r(q_far) + + + + + +""" +camera = [0.6293167471885681, + -9.560577392578125, + 10.504343032836914, + 0.9323806762695312, + 0.36073973774909973, + 0.008668755181133747, + 0.02139890193939209] +r.client.gui.setCameraTransform(0,camera) +""" + +""" +r.client.gui.removeFromGroup("rm",r.sceneName) +r.client.gui.removeFromGroup("rmstart",r.sceneName) +r.client.gui.removeFromGroup("rmgoal",r.sceneName) +for i in range(0,ps.numberNodes()): + r.client.gui.removeFromGroup("vecRM"+str(i),r.sceneName) + +""" + + +# Playing the computed path +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) +pp.dt=0.03 +pp.displayVelocityPath(0) +r.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP") +#display path +pp.speed=0.3 +#pp (0) + +#display path with post-optimisation + + + + +""" +q_far = q_init[::] +q_far[2] = -3 +r(q_far) +""" + + +""" +for i in range(1,10): + rbprmBuilder.client.basic.problem.optimizePath(i) + r.client.gui.removeFromGroup("path_"+str(i)+"_root",r.sceneName) + pp.displayVelocityPath(i+1) + #time.sleep(2) +""" + +""" +i=0 + +ps.clearRoadmap() +ps.solve() +r.client.gui.removeFromGroup("path_"+str(i)+"_root",r.sceneName) +i = i+1 +pp.displayVelocityPath(i) + +pp(i) + + +""" + +""" +r.client.gui.addCurve("c1",qlist,r.color.red) +r.client.gui.setVisibility("c1","ALWAYS_ON_TOP") +r.client.gui.addToGroup("c1",r.sceneName) + + +r.client.gui.addCurve("c2",qlist2,r.color.blue) +r.client.gui.setVisibility("c2","ALWAYS_ON_TOP") +r.client.gui.addToGroup("c2",r.sceneName) + + + +""" + + +