From 9a4078e1d6ddceebf227a29528cd3a7eab5887b1 Mon Sep 17 00:00:00 2001
From: Carlos Mastalli <carlos.mastalli@laas.fr>
Date: Mon, 11 Feb 2019 19:20:26 +0100
Subject: [PATCH] [action] Added documentation to the DAMLQR data

---
 crocoddyl/differential_action.py | 14 +++++++++-----
 1 file changed, 9 insertions(+), 5 deletions(-)

diff --git a/crocoddyl/differential_action.py b/crocoddyl/differential_action.py
index a40d3527..c2ab14e5 100644
--- a/crocoddyl/differential_action.py
+++ b/crocoddyl/differential_action.py
@@ -198,16 +198,16 @@ class DifferentialActionModelLQR(DifferentialActionModelAbstract):
 class DifferentialActionDataLQR:
   def __init__(self,model):
     nx,nu,ndx,nv,nout = model.nx,model.nu,model.State.ndx,model.nv,model.nout
+    # State evolution and cost data
     self.cost = np.nan
     self.xout = np.zeros(nout)
+
+    # Dynamics data
     self.F = np.zeros([ nout,ndx+nu ])
     self.Fx = self.F[:,:ndx]
     self.Fu = self.F[:,-nu:]
-    
-    self.Fx[:,:model.nv] = model.B
-    self.Fx[:,model.nv:] = model.A
-    self.Fu[:,:] = model.C
-    
+
+    # Cost data
     self.g = np.zeros( ndx+nu)
     self.L = np.zeros([ndx+nu,ndx+nu])
     self.Lx = self.g[:ndx]
@@ -216,6 +216,10 @@ class DifferentialActionDataLQR:
     self.Lxu = self.L[:ndx,ndx:]
     self.Luu = self.L[ndx:,ndx:]
 
+    # Setting the linear model and quadratic cost here because they are constant
+    self.Fx[:,:model.nv] = model.B
+    self.Fx[:,model.nv:] = model.A
+    self.Fu[:,:] = model.C
     np.copyto(self.Lxx, model.Q+model.Q.T)
     np.copyto(self.Lxu, np.zeros((nx, nu)))
     np.copyto(self.Luu, model.U+model.U.T)
-- 
GitLab