diff --git a/examples/bipedal_walking_from_foot_traj.py b/examples/bipedal_walking_from_foot_traj.py index 80b2a162f87833f09a7825da53dc4259b6609b86..912f6a46f44a22189ba1530abcefc04a99d9d428 100644 --- a/examples/bipedal_walking_from_foot_traj.py +++ b/examples/bipedal_walking_from_foot_traj.py @@ -210,7 +210,7 @@ walkProblem = walk.createProblem(x0, stepLength, timeStep, stepKnots, supportKno ddp = SolverDDP(walkProblem) cameraTF = [3., 3.68, 0.84, 0.2, 0.62, 0.72, 0.22] ddp.callback = [CallbackDDPLogger(), CallbackDDPVerbose(), - CallbackSolverDisplay(talos_legs,4,cameraTF)] + CallbackSolverDisplay(talos_legs,4,1,cameraTF)] ddp.th_stop = 1e-9 ddp.solve(maxiter=1000,regInit=.1,init_xs=[talos_legs.model.defaultState]*len(ddp.models())) diff --git a/examples/notebooks/bipedal_walking_from_foot_traj.ipynb b/examples/notebooks/bipedal_walking_from_foot_traj.ipynb index 30d28522569358c6b20c77d29f4c5a69079f1ef1..e1b64484f15dd704d2148f8b4f9746b6505678a1 100644 --- a/examples/notebooks/bipedal_walking_from_foot_traj.ipynb +++ b/examples/notebooks/bipedal_walking_from_foot_traj.ipynb @@ -284,7 +284,7 @@ "ddp = SolverDDP(walkProblem)\n", "cameraTF = [3., 3.68, 0.84, 0.2, 0.62, 0.72, 0.22]\n", "ddp.callback = [CallbackDDPLogger(), CallbackDDPVerbose(),\n", - " CallbackSolverDisplay(talos_legs,4,cameraTF)]\n", + " CallbackSolverDisplay(talos_legs,4,1,cameraTF)]\n", "ddp.th_stop = 1e-9\n", "ddp.solve(maxiter=1000,regInit=.1,init_xs=[talos_legs.model.defaultState]*len(ddp.models()))" ] diff --git a/examples/notebooks/introduction_to_crocoddyl.ipynb b/examples/notebooks/introduction_to_crocoddyl.ipynb index 8ba94c41d59c7d7cb31eef89e847e867d57cb77c..0d8367e59530a1d7fb0a87ef6ee8fbce32a70b9e 100644 --- a/examples/notebooks/introduction_to_crocoddyl.ipynb +++ b/examples/notebooks/introduction_to_crocoddyl.ipynb @@ -439,7 +439,7 @@ "# Creating the DDP solver for this OC problem, defining a logger\n", "ddp = SolverDDP(problem)\n", "cameraTF = [2., 2.68, 0.54, 0.2, 0.62, 0.72, 0.22]\n", - "ddp.callback = [CallbackDDPLogger(), CallbackDDPVerbose(1), CallbackSolverDisplay(talos_arm,4,cameraTF)]\n", + "ddp.callback = [CallbackDDPLogger(), CallbackDDPVerbose(1), CallbackSolverDisplay(talos_arm,4,1,cameraTF)]\n", "\n", "# Solving it with the DDP algorithm\n", "ddp.solve()\n", diff --git a/examples/notebooks/manipulator.ipynb b/examples/notebooks/manipulator.ipynb index ccb71454c6edd2b1c86ecc607e13d4d98cb98331..b6c42d9ef7bf15a84026e8dc9206d4d35b7bccb1 100644 --- a/examples/notebooks/manipulator.ipynb +++ b/examples/notebooks/manipulator.ipynb @@ -65,7 +65,7 @@ "# Creating the DDP solver for this OC problem, defining a logger\n", "ddp = SolverDDP(problem)\n", "cameraTF = [2., 2.68, 0.54, 0.2, 0.62, 0.72, 0.22]\n", - "ddp.callback = [ CallbackDDPVerbose(), CallbackSolverDisplay(robot,4,cameraTF) ]\n", + "ddp.callback = [ CallbackDDPVerbose(), CallbackSolverDisplay(robot,4,1,cameraTF) ]\n", "\n", "# Solving it with the DDP algorithm\n", "ddp.solve()\n", diff --git a/examples/talos_arm.py b/examples/talos_arm.py index 028a8ddc8c7d9f3623d553279c79d33064a24972..07b6dd47a5f74057c56c9bc64b1fa66249b4f798 100644 --- a/examples/talos_arm.py +++ b/examples/talos_arm.py @@ -64,7 +64,7 @@ problem = ShootingProblem(x0, [ runningModel ]*T, terminalModel) # Creating the DDP solver for this OC problem, defining a logger ddp = SolverDDP(problem) cameraTF = [2., 2.68, 0.54, 0.2, 0.62, 0.72, 0.22] -ddp.callback = [CallbackDDPLogger(), CallbackDDPVerbose(1), CallbackSolverDisplay(robot,4,cameraTF)] +ddp.callback = [CallbackDDPLogger(), CallbackDDPVerbose(1), CallbackSolverDisplay(robot,4,1,cameraTF)] # Solving it with the DDP algorithm ddp.solve()