diff --git a/script/dynamic/downSlope_hrp2_interp2.py b/script/dynamic/downSlope_hrp2_interp2.py new file mode 100644 index 0000000000000000000000000000000000000000..41471f408e6bad9e11efd11788300da114584b88 --- /dev/null +++ b/script/dynamic/downSlope_hrp2_interp2.py @@ -0,0 +1,107 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.gepetto import Viewer + +import downSlope_hrp2_pathKino2 as tp +import time + + + +packageName = "hrp2_14_description" +meshPackageName = "hrp2_14_description" +rootJointType = "freeflyer" +## +# Information to retrieve urdf and srdf files. +urdfName = "hrp2_14" +urdfSuffix = "_reduced" +srdfSuffix = "" + +fullBody = FullBody () + +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +fullBody.setJointBounds ("base_joint_xyz", [-2,5, 0, 2, 0.45, 1.8]) +fullBody.client.basic.robot.setDimensionExtraConfigSpace(tp.extraDof) + +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) + +#~ AFTER loading obstacles +rLegId = 'hrp2_rleg_rom' +rLeg = 'RLEG_JOINT0' +rLegOffset = [0,0,-0.105] +rLegNormal = [0,0,1] +rLegx = 0.09; rLegy = 0.05 +fullBody.addLimb(rLegId,rLeg,'',rLegOffset,rLegNormal, rLegx, rLegy, 20000, "EFORT_Normal", 0.1) + +lLegId = 'hrp2_lleg_rom' +lLeg = 'LLEG_JOINT0' +lLegOffset = [0,0,-0.105] +lLegNormal = [0,0,1] +lLegx = 0.09; lLegy = 0.05 +fullBody.addLimb(lLegId,lLeg,'',lLegOffset,rLegNormal, lLegx, lLegy, 20000, "EFORT_Normal", 0.1) + + + + +q_0 = fullBody.getCurrentConfig(); +#~ fullBody.createOctreeBoxes(r.client.gui, 1, rarmId, q_0,) + + +q_init =[0.1, -0.82, 0.648702, 1.0, 0.0 , 0.0, 0.0,0.0, 0.0, 0.0, 0.0,0.261799388, 0.174532925, 0.0, -0.523598776, 0.0, 0.0, 0.17,0.261799388, -0.174532925, 0.0, -0.523598776, 0.0, 0.0, 0.17,0.0, 0.0, -0.453785606, 0.872664626, -0.41887902, 0.0,0.0, 0.0, -0.453785606, 0.872664626, -0.41887902, 0.0,0,0,0,0,0,0]; r (q_init) +fullBody.setCurrentConfig (q_init) + +configSize = fullBody.getConfigSize() -fullBody.client.basic.robot.getDimensionExtraConfigSpace() + +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(0,tp.ps.pathLength(0))[0:7] +dir_init = tp.ps.configAtParam(0,0.01)[tp.indexECS:tp.indexECS+3] +acc_init = tp.ps.configAtParam(0,0.01)[tp.indexECS+3:tp.indexECS+6] +dir_goal = tp.ps.configAtParam(0,tp.ps.pathLength(0)-0.01)[tp.indexECS:tp.indexECS+3] +acc_goal = tp.ps.configAtParam(0,tp.ps.pathLength(0)-0.01)[tp.indexECS+3:tp.indexECS+6] + +robTreshold = 3 +# 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[::] + +fullBody.setStaticStability(False) +# Randomly generating a contact configuration at q_init +fullBody.setCurrentConfig (q_init) +r(q_init) +q_init = fullBody.generateContacts(q_init,dir_init,acc_init,robTreshold) +r(q_init) + +# Randomly generating a contact configuration at q_end +fullBody.setCurrentConfig (q_goal) +q_goal = fullBody.generateContacts(q_goal, dir_goal,acc_goal,robTreshold) + + +# specifying the full body configurations as start and goal state of the problem + +r(q_init) + + +fullBody.setStartState(q_init,[rLegId,lLegId]) +fullBody.setEndState(q_goal,[rLegId,lLegId]) + + + +configs = fullBody.interpolate(0.08,pathId=0,robustnessTreshold = robTreshold, filterStates = True) +print "number of configs :", len(configs) + + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (fullBody.client.basic, r) + +from fullBodyPlayer import Player +player = Player(fullBody,pp,tp,configs,draw=False,optim_effector=False,use_velocity=True,pathId = 0) + +player.displayContactPlan() + + + diff --git a/script/dynamic/downSlope_hrp2_pathKino2.py b/script/dynamic/downSlope_hrp2_pathKino2.py new file mode 100644 index 0000000000000000000000000000000000000000..1c6ca938301eea4e7662bacce2c6bfec196b6e9a --- /dev/null +++ b/script/dynamic/downSlope_hrp2_pathKino2.py @@ -0,0 +1,197 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer +from hpp.corbaserver import Client +from hpp.corbaserver.robot import Robot as Parent +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +class Robot (Parent): + rootJointType = 'freeflyer' + packageName = 'hpp-rbprm-corba' + meshPackageName = 'hpp-rbprm-corba' + # URDF file describing the trunk of the robot HyQ + urdfName = 'hrp2_trunk_flexible' + urdfSuffix = "" + srdfSuffix = "" + def __init__ (self, robotName, load = True): + Parent.__init__ (self, robotName, self.rootJointType, load) + self.tf_root = "base_footprint" + self.client.basic = Client () + self.load = load + + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'hrp2_trunk_flexible' +urdfNameRom = ['hrp2_larm_rom','hrp2_rarm_rom','hrp2_lleg_rom','hrp2_rleg_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", [-2,5, 0, 2, 0.45, 1.8]) +rbprmBuilder.setJointBounds('CHEST_JOINT0',[0,0]) +rbprmBuilder.setJointBounds('CHEST_JOINT1',[-0.5,0.3]) +rbprmBuilder.setJointBounds('HEAD_JOINT0',[0,0]) +rbprmBuilder.setJointBounds('HEAD_JOINT1',[0,0]) + +# The following lines set constraint on the valid configurations: +# a configuration is valid only if all limbs can create a contact ... +rbprmBuilder.setFilter(['hrp2_lleg_rom','hrp2_rleg_rom']) +rbprmBuilder.setAffordanceFilter('hrp2_lleg_rom', ['Support',]) +rbprmBuilder.setAffordanceFilter('hrp2_rleg_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]) +indexECS = rbprmBuilder.getConfigSize() - rbprmBuilder.client.basic.robot.getDimensionExtraConfigSpace() + +# Creating an instance of HPP problem solver and the viewer + +ps = ProblemSolver( rbprmBuilder ) +ps.client.problem.setParameter("aMax",aMax) +ps.client.problem.setParameter("vMax",vMax) +ps.client.problem.setParameter("sizeFootX",0.24) +ps.client.problem.setParameter("sizeFootY",0.14) +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.976296,0,0.21643961,0] +q_init[8] = -0.3 +q_init [0:3] = [-1.6, 1, 1.75]; 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] = [0.976296,0,0.21643961,0] +q_goal[8] = -0.3 +q_goal [0:3] = [-0.25, 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) + + + +""" + + +