From 68c293e11db26ab9c76a45f692c7fc23c332b4b3 Mon Sep 17 00:00:00 2001 From: Pierre Fernbach <pierre.fernbach@laas.fr> Date: Thu, 10 Nov 2016 13:52:00 +0100 Subject: [PATCH] add script with hyq kinodynamic (flat ground) --- script/dynamic/darpa_hyq_interp.py | 141 +++++++++++++++++++++++++++++ script/dynamic/darpa_hyq_path.py | 93 +++++++++++++++++++ 2 files changed, 234 insertions(+) create mode 100755 script/dynamic/darpa_hyq_interp.py create mode 100755 script/dynamic/darpa_hyq_path.py diff --git a/script/dynamic/darpa_hyq_interp.py b/script/dynamic/darpa_hyq_interp.py new file mode 100755 index 00000000..36de13f2 --- /dev/null +++ b/script/dynamic/darpa_hyq_interp.py @@ -0,0 +1,141 @@ +#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 darpa_hyq_path as tp + +from os import environ +ins_dir = environ['DEVEL_DIR'] +db_dir = ins_dir+"/install/share/hyq-rbprm/database/hyq_" + + +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.setJointBounds ("base_joint_xyz", [-2,5, -1, 1, 0.3, 4]) + +# Setting a number of sample configurations used +nbSamples = 20000 + +ps = tp.ProblemSolver(fullBody) +r = tp.Viewer (ps) + +rootName = 'base_joint_xyz' + +# Creating limbs +# cType is "_3_DOF": positional constraint, but no rotation (contacts are punctual) +cType = "_3_DOF" +# string identifying the limb +rLegId = 'rfleg' +# First joint of the limb, as in urdf file +rLeg = 'rf_haa_joint' +# Last joint of the limb, as in urdf file +rfoot = 'rf_foot_joint' +# Specifying the distance between last joint and contact surface +offset = [0.,-0.021,0.] +# Specifying the contact surface direction when the limb is in rest pose +normal = [0,1,0] +# Specifying the rectangular contact surface length +legx = 0.02; legy = 0.02 +# remaining parameters are the chosen heuristic (here, manipulability), and the resolution of the octree (here, 10 cm). + +def addLimbDb(limbId, heuristicName, loadValues = True, disableEffectorCollision = False): + fullBody.addLimbDatabase(str(db_dir+limbId+'.db'), limbId, heuristicName,loadValues, disableEffectorCollision) + +lLegId = 'lhleg' +rarmId = 'rhleg' +larmId = 'lfleg' + +addLimbDb(rLegId, "static") +addLimbDb(lLegId, "static") +addLimbDb(rarmId, "static") +addLimbDb(larmId, "static") + +#~ fullBody.addLimb(rLegId,rLeg,rfoot,offset,normal, legx, legy, nbSamples, "jointlimits", 0.1, cType) + +lLegId = 'lhleg' +lLeg = 'lh_haa_joint' +lfoot = 'lh_foot_joint' +#~ fullBody.addLimb(lLegId,lLeg,lfoot,offset,normal, legx, legy, nbSamples, "jointlimits", 0.05, cType) +#~ +rarmId = 'rhleg' +rarm = 'rh_haa_joint' +rHand = 'rh_foot_joint' +#~ fullBody.addLimb(rarmId,rarm,rHand,offset,normal, legx, legy, nbSamples, "jointlimits", 0.05, cType) + +larmId = 'lfleg' +larm = 'lf_haa_joint' +lHand = 'lf_foot_joint' +#~ fullBody.addLimb(larmId,larm,lHand,offset,normal, legx, legy, nbSamples, "jointlimits", 0.05, cType) + +q_0 = fullBody.getCurrentConfig(); +q_init = fullBody.getCurrentConfig(); q_init[0:7] = tp.q_init[0:7] +q_goal = fullBody.getCurrentConfig(); q_goal[0:7] = tp.q_goal[0:7] + +# Randomly generating a contact configuration at q_init +fullBody.setCurrentConfig (q_init) +q_init = fullBody.generateContacts(q_init, [0,0,1]) + +# Randomly generating a contact configuration at q_end +fullBody.setCurrentConfig (q_goal) +q_goal = fullBody.generateContacts(q_goal, [0,0,1]) + +# specifying the full body configurations as start and goal state of the problem +fullBody.setStartState(q_init,[]) +fullBody.setEndState(q_goal,[rLegId,lLegId,rarmId,larmId]) + + +r(q_init) +# computing the contact sequence +configs = fullBody.interpolate(0.12, 10, 10, True) +#~ configs = fullBody.interpolate(0.11, 7, 10, True) +#~ configs = fullBody.interpolate(0.1, 1, 5, True) + +#~ r.loadObstacleModel ('hpp-rbprm-corba', "darpa", "contact") + +# calling draw with increasing i will display the sequence +i = 0; +fullBody.draw(configs[i],r); i=i+1; i-1 + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (fullBody.client.basic, r) + + +from hpp.corbaserver.rbprm.tools.cwc_trajectory_helper import step, clean,stats, saveAllData, play_traj + + + +limbsCOMConstraints = { rLegId : {'file': "hyq/"+rLegId+"_com.ineq", 'effector' : rfoot}, + lLegId : {'file': "hyq/"+lLegId+"_com.ineq", 'effector' : lfoot}, + rarmId : {'file': "hyq/"+rarmId+"_com.ineq", 'effector' : rHand}, + larmId : {'file': "hyq/"+larmId+"_com.ineq", 'effector' : lHand} } + + +def act(i, numOptim = 0, use_window = 0, friction = 0.5, optim_effectors = True, verbose = False, draw = False): + return step(fullBody, configs, i, numOptim, pp, limbsCOMConstraints, 0.4, optim_effectors = optim_effectors, time_scale = 20., useCOMConstraints = True, use_window = use_window, + verbose = verbose, draw = draw) + +def play(frame_rate = 1./24.): + play_traj(fullBody,pp,frame_rate) + +def saveAll(name): + saveAllData(fullBody, r, name) +#~ fullBody.exportAll(r, trajec, 'hole_hyq_t_var_04f_andrea'); +#~ fullBody.exportAll(r, configs, 'hole_hyq_t_var_04f_andrea_contact_planning'); +#~ saveToPinocchio('obstacle_hyq_t_var_04f_andrea') + +#~ fullBody.exportAll(r, trajec, 'darpa_hyq_t_var_04f_andrea'); +#~ saveToPinocchio('darpa_hyq_t_var_04f_andrea') diff --git a/script/dynamic/darpa_hyq_path.py b/script/dynamic/darpa_hyq_path.py new file mode 100755 index 00000000..5d0c891b --- /dev/null +++ b/script/dynamic/darpa_hyq_path.py @@ -0,0 +1,93 @@ +# 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_large' +# 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 = 2; +aMax = 1; +# 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", [-2,5, -1, 1, 0.5, 0.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. +rbprmBuilder.boundSO3([-0.4,0.4,-3,3,-3,3]) +rbprmBuilder.client.basic.robot.setDimensionExtraConfigSpace(2*3) +rbprmBuilder.client.basic.robot.setExtraConfigSpaceBounds([-vMax,vMax,-vMax,vMax,0,0,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.loadObstacleModel (packageName, "ground", "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 [0:3] = [-5, 0, 0.63]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +q_goal = q_init [::] +q_goal [0:3] = [4, 0, 0.63]; r (q_goal) +#~ q_goal [0:3] = [-1.5, 0, 0.63]; r (q_goal) + +# Choosing a path optimizer +ps.addPathOptimizer ("RandomShortcut") +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("Kinodynamic") +ps.selectDistance("KinodynamicDistance") +ps.selectPathPlanner("dynamicPlanner") + +#solve the problem : +r(q_init) +ps.solve () + + +# Playing the computed path +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) +pp.dt=0.03 +#r.client.gui.removeFromGroup("rm0",r.sceneName) +pp.displayVelocityPath(0) +#display path +pp (0) +#display path with post-optimisation +r.client.gui.removeFromGroup("path_0_root",r.sceneName) +pp.displayVelocityPath(1) +pp (1) + + +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) + + -- GitLab