diff --git a/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py b/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py
index b1346863f51af787341ce0360237449a9340d1d5..2c050cb41cb10b9e366858bb1f95b50a92bc4088 100644
--- a/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py
+++ b/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py
@@ -11,31 +11,63 @@ import pinocchio.casadi as cpin
 
 
 class NodeData:
+    """
+    Data stored by each shooting node of the OCP
+
+    Attributes:
+        x (vector): State vector (q + dq)
+        cost (float): Cost for this node
+        isTerminal (bool): True if last node of shooting problem
+        a (vector): Acceleration slack variables (ddq)
+        u (vector): Control vector (tau)
+        f (vector): Contact forces
+        xnext (vector): Next state vector
+    """
+
     def __init__(self, isTerminal=False):
-        self.x = None  # State vector (q + dq)
-        self.cost = None  # Cost for this node
-        self.isTerminal = isTerminal  # True if last node of shooting problem
+        self.x = None
+        self.cost = None
+        self.isTerminal = isTerminal
         if not isTerminal:
-            self.a = None  # Acceleration slack variables (ddq)
-            self.u = None  # Control vector (tau)
-            self.f = None  # Contact forces
-            self.xnext = None  # Next state vector
+            self.a = None
+            self.u = None
+            self.f = None
+            self.xnext = None
 
 
 class OcpResult:
+    """
+    Result of the OCP
+
+    Attributes:
+        xs (vector): State trajectory (q + dq)
+        a (vector): Acceleration trajectory (ddq)
+        us (vector): Control trajectory (tau)
+        fs (vector): Contact forces trajectories
+    """
+
     def __init__(self):
-        self.xs = None  # State trajectory (q + dq)
-        self.a = None  # Acceleration trajectory (ddq)
-        self.us = None  # Control trajectory (tau)
-        self.fs = None  # Contact forces trajectories
-        # self.K = None
-        # self.f_world = None
-        # self.q = None
-        # self.v = None
-        # self.solver_time = None
+        self.xs = None
+        self.a = None
+        self.us = None
+        self.fs = None
 
 
 class OCP:
+    """
+    Optimal Control Problem
+
+    Args:
+        pd (ProblemData): data related to the OCP
+        gait (list): list of list containing contact pattern i.e. for two steps[[1,1,1,1], [1,0,0,1]]
+            Its length determines the horizon of the ocp
+
+    Attributes:
+        pd (ProblemData): data related to the OCP
+        results (OcpResult): result of the OCP
+        shooting_nodes (set): set of shooting nodes of the OCP
+    """
+
     def __init__(self, pd: ProblemData, tasks, gait):
         """Define an optimal ocntrol problem.
         :param robot: Pinocchio RobotWrapper instance