diff --git a/script/scenarios/demos/hrp2_flatGround.py b/script/scenarios/demos/hrp2_flatGround.py
new file mode 100644
index 0000000000000000000000000000000000000000..d0afe53fd8b2f9cc7cebd2096fea7f2e87efacc5
--- /dev/null
+++ b/script/scenarios/demos/hrp2_flatGround.py
@@ -0,0 +1,101 @@
+from hpp.corbaserver.rbprm.hrp2 import Robot
+from hpp.gepetto import Viewer
+from tools.display_tools import *
+import time
+print "Plan guide trajectory ..."
+import hrp2_flatGround_path as tp
+print "Done."
+import time
+
+pId = tp.ps.numberPaths() -1
+fullBody = Robot ()
+
+# Set the bounds for the root
+fullBody.setJointBounds ("root_joint",  [-5,5, -1.5, 1.5, 0.5, 0.8])
+fullBody.setJointBounds("LLEG_JOINT3",[0.4,2.61799]) # increase min bounds on knee, required to stay in the 'comfort zone' of the stabilizer
+fullBody.setJointBounds("RLEG_JOINT3",[0.4,2.61799])
+# TODO : fix rot y legs
+# 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
+v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = True)
+
+# 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.setCurrentConfig (q_init)
+v(q_ref)
+print "Generate limb DB ..."
+tStart = time.time()
+# generate databases : 
+
+nbSamples = 100000
+fullBody.addLimb(fullBody.rLegId,fullBody.rleg,'',fullBody.rLegOffset,fullBody.rLegNormal, fullBody.rLegx, fullBody.rLegy, nbSamples, "fixedStep06", 0.01,limbOffset=fullBody.rLegLimbOffset,kinematicConstraintsPath=fullBody.rLegKinematicConstraints,kinematicConstraintsMin = 0.4)
+fullBody.runLimbSampleAnalysis(fullBody.rLegId, "ReferenceConfiguration", True)
+fullBody.addLimb(fullBody.lLegId,fullBody.lleg,'',fullBody.lLegOffset,fullBody.lLegNormal, fullBody.lLegx, fullBody.lLegy, nbSamples, "fixedStep06", 0.01,limbOffset=fullBody.lLegLimbOffset,kinematicConstraintsPath=fullBody.lLegKinematicConstraints,kinematicConstraintsMin = 0.4)
+fullBody.runLimbSampleAnalysis(fullBody.lLegId, "ReferenceConfiguration", True)
+"""
+fullBody.addLimb(fullBody.rArmId,fullBody.rarm,fullBody.rhand,fullBody.rArmOffset,fullBody.rArmNormal, fullBody.rArmx, fullBody.rArmy, nbSamples, "static", 0.01,kinematicConstraintsPath=fullBody.rArmKinematicConstraints)
+fullBody.runLimbSampleAnalysis(fullBody.rArmId, "ReferenceConfiguration", True)
+fullBody.addLimb(fullBody.lArmId,fullBody.larm,fullBody.lhand,fullBody.lArmOffset,fullBody.lArmNormal, fullBody.lArmx, fullBody.lArmy, nbSamples, "static", 0.01,kinematicConstraintsPath=fullBody.lArmKinematicConstraints)
+fullBody.runLimbSampleAnalysis(fullBody.lArmId, "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.01)[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]
+dir_init = tp.ps.configAtParam(pId,0.01)[tp.indexECS:tp.indexECS+3]
+acc_init = tp.ps.configAtParam(pId,0.01)[tp.indexECS+3:tp.indexECS+6]
+dir_goal = tp.ps.configAtParam(pId,tp.ps.pathLength(pId)-0.01)[tp.indexECS:tp.indexECS+3]
+acc_goal = [0,0,0]
+
+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] = [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('hrp2_14/base_link',0.3)
+v(q_init)
+
+# specify the full body configurations as start and goal state of the problem
+fullBody.setStartState(q_init,[fullBody.rLegId,fullBody.lLegId])
+fullBody.setEndState(q_goal,[fullBody.rLegId,fullBody.lLegId])
+
+
+print "Generate contact plan ..."
+tStart = time.time()
+configs = fullBody.interpolate(0.01,pathId=pId,robustnessTreshold = 1., filterStates = True,testReachability = False, quasiStatic = False)
+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)
+
diff --git a/script/scenarios/demos/hrp2_flatGround_path.py b/script/scenarios/demos/hrp2_flatGround_path.py
new file mode 100644
index 0000000000000000000000000000000000000000..24b5bccb4c1ece50683726c7ffabb0ea9ea3d053
--- /dev/null
+++ b/script/scenarios/demos/hrp2_flatGround_path.py
@@ -0,0 +1,95 @@
+from hpp.corbaserver.rbprm.hrp2_abstract import Robot
+from hpp.gepetto import Viewer
+from hpp.corbaserver import ProblemSolver
+import time
+
+
+
+vMax = 0.2# linear velocity bound for the root
+aMax = 0.1# linear acceleration bound for the root
+extraDof = 6
+mu=0.5# coefficient of friction
+# Creating an instance of the helper class, and loading the robot
+rbprmBuilder = Robot ()
+# Define bounds for the root : bounding box of the scenario
+rbprmBuilder.setJointBounds ("root_joint", [-5,5, -1.5, 1.5, 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 with the corresponding afforcances type
+rbprmBuilder.setFilter([Robot.rLegId,Robot.lLegId])
+rbprmBuilder.setAffordanceFilter(Robot.rLegId, ['Support',])
+rbprmBuilder.setAffordanceFilter(Robot.lLegId, ['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",Robot.legX*2.)
+ps.setParameter("DynamicPlanner/sizeFootY",Robot.legY*2.)
+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)
+v = vf.createViewer(displayArrows = True)
+#afftool.visualiseAffordances('Support', v, v.color.lightBrown)
+
+# Setting initial configuration
+q_init = rbprmBuilder.getCurrentConfig ();
+q_init[3:7] = [0,0,0,1]
+q_init [0:3] = [0, 0, 0.6]
+v (q_init)
+ps.setInitialConfig (q_init)
+# set goal config
+rbprmBuilder.setCurrentConfig (q_init)
+q_goal = q_init [::]
+q_goal[0] = 1.5
+v(q_goal)
+
+
+ps.addGoalConfig (q_goal)
+
+# Choosing RBPRM shooter and path validation methods.
+ps.selectConfigurationShooter("RbprmShooter")
+ps.addPathOptimizer ("RandomShortcutDynamic")
+ps.selectPathValidation("RbprmPathValidation",0.05)
+# Choosing kinodynamic methods :
+ps.selectSteeringMethod("RBPRMKinodynamic")
+ps.selectDistance("Kinodynamic")
+ps.selectPathPlanner("DynamicPlanner")
+
+# Solve the planning problem :
+t = ps.solve ()
+print "Guide planning time : ",t
+
+
+# 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)
+
+# move the robot out of the view before computing the contacts
+q_far = q_init[::]
+q_far[2] = -2
+v(q_far)
+