From f447cf9abe191fa427cfbfa89c84331d0e27ddc0 Mon Sep 17 00:00:00 2001 From: paleziart <paleziart@laas.fr> Date: Mon, 23 Jan 2023 13:43:26 +0100 Subject: [PATCH] Change optimization variables from dxs to xs directly (bis) --- python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py b/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py index cb1ac42b..0d30c307 100644 --- a/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py +++ b/python/quadruped_reactive_walking/WB_MPC/CasadiOCP.py @@ -71,7 +71,6 @@ class OCP: datas (list of NodeData): list of node data, one for each node of the OCP opti (casadi.Opti): optimization problem wrapper xs (vector): State trajectory (q + dq) - dxs (vector): Derivative of state trajectory a (vector): Acceleration slack trajectory us (vector): Control trajectory (tau) fs (vector): Contact forces trajectories @@ -204,10 +203,6 @@ class OCP: self.opti = opti # Optimization variables - self.dxs = [ - opti.variable(self.pd.ndx) - for _ in self.runningModels + [self.terminalModel] - ] self.acs = [opti.variable(self.pd.nv) for _ in self.runningModels] self.us = [opti.variable(self.pd.nu) for _ in self.runningModels] self.xs = [opti.variable(self.pd.nx) for _ in (self.runningModels + [self.terminalModel])] -- GitLab