diff --git a/crocoddyl/differential_action.py b/crocoddyl/differential_action.py
index d95fe56b5be30a12c2f9dd1898c4628b9f36b7cd..5426fac24a1543e9d48c0a89327222c011090ffb 100644
--- a/crocoddyl/differential_action.py
+++ b/crocoddyl/differential_action.py
@@ -25,14 +25,15 @@ class DifferentialActionModelAbstract:
         self.unone = np.zeros(self.nu)
 
     def createData(self):
-        """ Created the differential action data.
+        """ Create the differential action data.
 
         Each differential action model has its own data that needs to be
         allocated. This function returns the allocated data for a predefined
-        DAM.
+        DAM. Note that you need to defined the DifferentialActionDataType inside
+        your DAM.
         :return DAM data.
         """
-        raise NotImplementedError("Not implemented yet.")
+        return self.DifferentialActionDataType(self)
 
     def calc(model, data, x, u=None):
         """ Compute the state evolution and cost value.
@@ -102,6 +103,7 @@ class DifferentialActionModelFullyActuated(DifferentialActionModelAbstract):
     def __init__(self, pinocchioModel, costModel):
         DifferentialActionModelAbstract.__init__(
             self, pinocchioModel.nq, pinocchioModel.nv, pinocchioModel.nv)
+        self.DifferentialActionDataType = DifferentialActionDataFullyActuated
         self.pinocchio = pinocchioModel
         self.State = StatePinocchio(self.pinocchio)
         self.costs = costModel
@@ -110,7 +112,6 @@ class DifferentialActionModelFullyActuated(DifferentialActionModelAbstract):
         self.forceAba = False
     @property
     def ncost(self): return self.costs.ncost
-    def createData(self): return DifferentialActionDataFullyActuated(self)
     def calc(model,data,x,u=None):
         if u is None: u=model.unone
         nq,nv = model.nq,model.nv
@@ -181,6 +182,7 @@ class DifferentialActionModelLQR(DifferentialActionModelAbstract):
   """
   def __init__(self, nq, nu):
     DifferentialActionModelAbstract.__init__(self, nq, nq, nu)
+    self.DifferentialActionDataType = DifferentialActionDataLQR
     self.State = StateVector(self.nx)
 
     v1 = randomOrthonormalMatrix(self.nq)
@@ -195,9 +197,6 @@ class DifferentialActionModelLQR(DifferentialActionModelAbstract):
     self.Q = randomOrthonormalMatrix(self.nx)
     self.U = randomOrthonormalMatrix(self.nu)
 
-  def createData(self):
-      return DifferentialActionDataLQR(self)
-
   def calc(model,data,x,u=None):
     q = x[:model.nq]; v = x[model.nq:]
     data.xout[:] = (np.dot(model.A, v) + np.dot(model.B, q) + np.dot(model.C, u)).flat + model.d
@@ -227,6 +226,7 @@ class DifferentialActionDataLQR(DifferentialActionDataAbstract):
 
 class DifferentialActionModelNumDiff(DifferentialActionModelAbstract):
     def __init__(self,model,withGaussApprox=False):
+        self.DifferentialActionDataType = DifferentialActionDataNumDiff
         self.model0 = model
         self.nx = model.nx
         self.ndx = model.ndx
@@ -243,8 +243,6 @@ class DifferentialActionModelNumDiff(DifferentialActionModelAbstract):
         self.withGaussApprox = withGaussApprox
         assert( not self.withGaussApprox or self.ncost>1 )
 
-    def createData(self):
-        return DifferentialActionDataNumDiff(self)
     def calc(model,data,x,u): return model.model0.calc(data.data0,x,u)
     def calcDiff(model,data,x,u,recalc=True):
         xn0,c0 = model.calc(data,x,u)
diff --git a/crocoddyl/floating_contact.py b/crocoddyl/floating_contact.py
index bf411fb40dbd6e9ce020a912d12bdfbae086f6d1..4cbf4120e45699db3f1cc344cbe5e019ee7f22a5 100644
--- a/crocoddyl/floating_contact.py
+++ b/crocoddyl/floating_contact.py
@@ -10,6 +10,7 @@ class DifferentialActionModelFloatingInContact(DifferentialActionModelAbstract):
     def __init__(self,pinocchioModel,actuationModel,contactModel,costModel):
         DifferentialActionModelAbstract.__init__(
             self, pinocchioModel.nq, pinocchioModel.nv, actuationModel.nu)
+        self.DifferentialActionDataType = DifferentialActionDataFloatingInContact
         self.pinocchio = pinocchioModel
         self.State = StatePinocchio(self.pinocchio)
         self.actuation = actuationModel
@@ -19,7 +20,6 @@ class DifferentialActionModelFloatingInContact(DifferentialActionModelAbstract):
     def ncost(self): return self.costs.ncost
     @property
     def ncontact(self): return self.contact.ncontact
-    def createData(self): return DifferentialActionDataFloatingInContact(self)
     def calc(model,data,x,u=None):
         if u is None: u=model.unone
         nq,nv = model.nq,model.nv