diff --git a/script/scenarios/demos/talos_flatGround_interp.py b/script/scenarios/demos/talos_flatGround.py
similarity index 98%
rename from script/scenarios/demos/talos_flatGround_interp.py
rename to script/scenarios/demos/talos_flatGround.py
index a7f0085a164b648011513325e344ac8ed07cdb7c..7b553ab98700d0730ca9f46469d66af2cf12352c 100644
--- a/script/scenarios/demos/talos_flatGround_interp.py
+++ b/script/scenarios/demos/talos_flatGround.py
@@ -1,4 +1,3 @@
-from hpp.corbaserver.rbprm.rbprmbuilder import Builder
 from hpp.corbaserver.rbprm.rbprmfullbody import FullBody
 from hpp.gepetto import Viewer
 from display_tools import *
@@ -64,8 +63,6 @@ q_init = q_ref[::]
 fullBody.setReferenceConfig(q_ref)
 
 fullBody.setCurrentConfig (q_init)
-qfar=q_ref[::]
-qfar[2] = -5
 
 print "Generate limb DB ..."
 tStart = time.time()
diff --git a/script/scenarios/demos/talos_navBauzil.py b/script/scenarios/demos/talos_navBauzil.py
new file mode 100644
index 0000000000000000000000000000000000000000..e39533e1aac6eeab59136e2d3b7f6230d01e0cdd
--- /dev/null
+++ b/script/scenarios/demos/talos_navBauzil.py
@@ -0,0 +1,152 @@
+from hpp.corbaserver.rbprm.rbprmfullbody import FullBody
+from hpp.gepetto import Viewer
+from display_tools import *
+import time
+from hpp.corbaserver.rbprm.rbprmstate import State,StateHelper
+print "Plan guide trajectory ..."
+import talos_navBauzil_path as tp
+print "Done."
+import time
+
+##
+#  Information to retrieve urdf and srdf files.
+packageName = "talos_data"
+meshPackageName = "talos_data"
+rootJointType = "freeflyer"    
+urdfName = "talos"
+urdfSuffix = "_reduced"
+srdfSuffix = ""
+
+
+rLegId = 'talos_rleg_rom'
+rleg = 'leg_right_1_joint'
+rfoot = 'leg_right_6_joint'
+
+lLegId = 'talos_lleg_rom'
+lleg = 'leg_left_1_joint'
+lfoot = 'leg_left_6_joint'
+
+rArmId = 'talos_rarm_rom'
+rarm = 'arm_right_1_joint'
+rhand = 'arm_right_7_joint'
+
+lArmId = 'talos_larm_rom'
+larm = 'arm_left_1_joint'
+lhand = 'arm_left_7_joint'
+
+
+pId = tp.ps.numberPaths() -1
+fullBody = FullBody ()
+
+fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix)
+root_bounds = tp.root_bounds[::]
+root_bounds[0] -= 0.2
+root_bounds[1] += 0.2
+root_bounds[2] -= 0.2
+root_bounds[3] += 0.2
+root_bounds[-1] = 1.2
+root_bounds[-2] = 0.8
+fullBody.setJointBounds ("root_joint",  root_bounds)
+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)
+v = tp.Viewer (ps,viewerClient=tp.v.client, displayCoM = True)
+
+
+q_ref = [
+        0.0, 0.0,  1.0232773,  0.0 ,  0.0, 0.0, 1.,                   #Free flyer
+        0.0,  0.0, -0.411354,  0.859395, -0.448041, -0.001708,          #Left Leg
+        0.0,  0.0, -0.411354,  0.859395, -0.448041, -0.001708,          #Right Leg
+        0.0 ,  0.006761,                                                #Chest
+        0.25847 ,  0.173046, -0.0002, -0.525366, 0.0, -0.0,  0.1,-0.005,  #Left Arm
+        -0.25847 , -0.173046, 0.0002  , -0.525366, 0.0,  0.0,  0.1,-0.005,#Right Arm
+        0.,  0.  ,                                                       #Head
+        0,0,0,0,0,0]; v (q_ref)
+
+q_init = q_ref[::]
+
+fullBody.setReferenceConfig(q_ref)
+fullBody.setCurrentConfig (q_init)
+
+
+print "Generate limb DB ..."
+tStart = time.time()
+# generate databases : 
+
+nbSamples = 10000
+rLegOffset = [0.,  -0.00018, -0.107]
+rLegOffset[2] += 0.006
+rLegNormal = [0,0,1]
+rLegx = 0.1; rLegy = 0.06
+fullBody.addLimb(rLegId,rleg,rfoot,rLegOffset,rLegNormal, rLegx, rLegy, nbSamples, "fixedStep08", 0.01)
+fullBody.runLimbSampleAnalysis(rLegId, "ReferenceConfiguration", True)
+#fullBody.saveLimbDatabase(rLegId, "./db/talos_rLeg_walk.db")
+
+lLegOffset = [0.,  -0.00018, -0.107]
+lLegOffset[2] += 0.006
+lLegNormal = [0,0,1]
+lLegx = 0.1; lLegy = 0.06
+fullBody.addLimb(lLegId,lleg,lfoot,lLegOffset,rLegNormal, lLegx, lLegy, nbSamples, "fixedStep08", 0.01)
+fullBody.runLimbSampleAnalysis(lLegId, "ReferenceConfiguration", True)
+#fullBody.saveLimbDatabase(rLegId, "./db/talos_lLeg_walk.db")
+
+
+
+tGenerate =  time.time() - tStart
+print "Done."
+print "Databases generated in : "+str(tGenerate)+" s"
+
+
+q_0 = fullBody.getCurrentConfig(); 
+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)
+
+# specifying the full body configurations as start and goal state of the problem
+v.addLandmark('talos/base_link',0.3)
+v(q_init)
+
+fullBody.setStartState(q_init,[lLegId,rLegId])
+fullBody.setEndState(q_goal,[lLegId,rLegId])
+
+
+from hpp.gepetto import PathPlayer
+pp = PathPlayer ( v)
+
+print "Generate contact plan ..."
+tStart = time.time()
+configs = fullBody.interpolate(0.01,pathId=pId,robustnessTreshold = 2, filterStates = False)
+tInterpolateConfigs = time.time() - tStart
+print "Done."
+print "number of configs :", len(configs)
+raw_input("Press Enter to display the contact sequence ...")
+displayContactSequence(v,configs)
+
+
+
diff --git a/script/scenarios/demos/talos_navBauzil_path.py b/script/scenarios/demos/talos_navBauzil_path.py
new file mode 100644
index 0000000000000000000000000000000000000000..ccc3f706a767a72450b0fb48b46d3d655ffe3cf5
--- /dev/null
+++ b/script/scenarios/demos/talos_navBauzil_path.py
@@ -0,0 +1,104 @@
+from hpp.corbaserver.rbprm.rbprmbuilder import Builder
+from hpp.gepetto import Viewer
+from hpp.corbaserver import Client
+from hpp.corbaserver import ProblemSolver
+import time
+
+
+
+
+rootJointType = 'freeflyer'
+packageName = 'talos-rbprm'
+meshPackageName = 'talos-rbprm'
+urdfName = 'talos_trunk'
+urdfNameRom =  ['talos_larm_rom','talos_rarm_rom','talos_lleg_rom','talos_rleg_rom']
+urdfSuffix = ""
+srdfSuffix = ""
+vMax = 0.3
+aMax = 0.1
+extraDof = 6
+mu=0.5
+# Creating an instance of the helper class, and loading the robot
+rbprmBuilder = Builder ()
+rbprmBuilder.loadModel(urdfName, urdfNameRom, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix)
+root_bounds = [-2.3,4.6,-1.5,3.3, 0.98, 0.98]
+rbprmBuilder.setJointBounds ("root_joint", root_bounds)
+rbprmBuilder.setJointBounds ('torso_1_joint', [0,0])
+rbprmBuilder.setJointBounds ('torso_2_joint', [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(['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([-4.,4.,-0.1,0.1,-0.1,0.1])
+rbprmBuilder.client.robot.setDimensionExtraConfigSpace(extraDof)
+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 and the viewer
+
+ps = ProblemSolver( rbprmBuilder )
+ps.setParameter("Kinodynamic/velocityBound",vMax)
+ps.setParameter("Kinodynamic/accelerationBound",aMax)
+#ps.setParameter("Kinodynamic/forceOrientation",True)
+ps.setParameter("DynamicPlanner/sizeFootX",0.2)
+ps.setParameter("DynamicPlanner/sizeFootY",0.12)
+ps.setParameter("DynamicPlanner/friction",mu)
+ps.setParameter("ConfigurationShooter/sampleExtraDOF",False)
+
+
+from hpp.gepetto import ViewerFactory
+vf = ViewerFactory (ps)
+
+from hpp.corbaserver.affordance.affordance import AffordanceTool
+afftool = AffordanceTool ()
+afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005])
+afftool.loadObstacleModel ("hpp-rbprm-corba", "floor_bauzil", "planning", vf)
+v = vf.createViewer(displayArrows = True)
+afftool.visualiseAffordances('Support', v, v.color.lightBrown)
+
+# Setting initial configuration
+q_init = rbprmBuilder.getCurrentConfig ();
+q_init [0:3] = [-0.9,1.5,0.98]
+q_init[-6:-3] = [0.07,0,0]
+v (q_init)
+
+# set goal config
+rbprmBuilder.setCurrentConfig (q_init)
+q_goal = q_init [::]
+q_goal[0:3] = [2,2.6,0.98]
+q_goal[-6:-3] = [0.1,0,0]
+v(q_goal)
+
+ps.setInitialConfig (q_init)
+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")
+
+
+t = ps.solve ()
+print "Guide planning time : ",t
+
+
+# display solution : 
+from hpp.gepetto import PathPlayer
+pp = PathPlayer (v)
+pp.dt=0.03
+pp.displayVelocityPath(0)
+v.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP")
+pp(0)
+
+
+q_far = q_init[::]
+q_far[2] = -2
+v(q_far)
+