diff --git a/config/walk_parameters.yaml b/config/walk_parameters.yaml
index ce736c5b3621ade768195b9de1a0ef78d9ccda23..95225b9b7d904eb3887c91723803598a8955e8ad 100644
--- a/config/walk_parameters.yaml
+++ b/config/walk_parameters.yaml
@@ -13,7 +13,7 @@ robot:
     predefined_vel: true  # If we are using a predefined reference velocity (True) or a joystick (False)
     N_SIMULATION: 5000  # Number of simulated wbc time steps
     enable_corba_viewer: false  # Enable/disable Corba Viewer
-    enable_multiprocessing: true  # Enable/disable running the MPC in another process in parallel of the main loop
+    enable_multiprocessing: false  # Enable/disable running the MPC in another process in parallel of the main loop
     perfect_estimator: true  # Enable/disable perfect estimator by using data directly from PyBullet
 
     # General control parameters
@@ -25,7 +25,7 @@ robot:
     dt_mpc: 0.015  # Time step of the model predictive control
     type_MPC: 3  # Which MPC solver you want to use: 0 for OSQP MPC, 1, 2, 3 for Crocoddyl MPCs
     save_guess: false # true to interpolate the impedance quantities between nodes of the MPC
-    movement: "step" # name of the movement to perform
+    movement: "circle" # name of the movement to perform
     interpolate_mpc: false # true to interpolate the impedance quantities between nodes of the MPC
     interpolation_type: 3 # 0,1,2,3 decide which kind of interpolation is used
     # Kp_main: [0.0, 0.0, 0.0]  # Proportional gains for the PD+
diff --git a/python/quadruped_reactive_walking/WB_MPC/CrocoddylOCP.py b/python/quadruped_reactive_walking/WB_MPC/CrocoddylOCP.py
index 3cd46774136669cea0110d4f33096b3794074443..571dde8e3cd5ed413ef72f596b1ee19f3183ef9b 100644
--- a/python/quadruped_reactive_walking/WB_MPC/CrocoddylOCP.py
+++ b/python/quadruped_reactive_walking/WB_MPC/CrocoddylOCP.py
@@ -12,7 +12,7 @@ from time import time
 class OCP:
     def __init__(self, pd: ProblemData, footsteps, gait):
         self.pd = pd
-        self.max_iter = 1000
+        self.max_iter = 1
 
         self.state = crocoddyl.StateMultibody(self.pd.model)
         self.initialized = False
diff --git a/python/quadruped_reactive_walking/WB_MPC/ProblemData.py b/python/quadruped_reactive_walking/WB_MPC/ProblemData.py
index 286fd78dea607a0aa68fba012abf493087ee3c8e..663c04f7c881dc7188cf47b58e936b6bf3658367 100644
--- a/python/quadruped_reactive_walking/WB_MPC/ProblemData.py
+++ b/python/quadruped_reactive_walking/WB_MPC/ProblemData.py
@@ -181,11 +181,11 @@ class ProblemDataFull(problemDataAbstract):
         # Cost function weights
         # Cost function weights
         self.mu = 0.7
-        self.foot_tracking_w = 1e5
+        self.foot_tracking_w = 1e4
         # self.friction_cone_w = 1e3 * 0
         self.control_bound_w = 1e3
         self.control_reg_w = 1e-1
-        self.state_reg_w = np.array([1e-1] * 3 + [1e-1] * 3)
+        self.state_reg_w = np.array([1e-1] * 3 + [1e0] * 3)
         self.terminal_velocity_w = np.array([0] * 3 + [1e3] * 3)
 
         self.q0_reduced = self.q0[10:13]