Issue with cost_expr_ext_cost_0

Hi
I’m getting an error with acados when using the EXTERNAL cost function.

I have a 3-DoF linear system:

# Define state
pos = cs.MX.sym('p', 3)
vel = cs.MX.sym('v', 3)
z = cs.vertcat(pos, vel)

# Define state derivative
pos_d = cs.MX.sym('p_dot', 3)
vel_d = cs.MX.sym('v_dot', 3)
z_d = cs.vertcat(pos, vel)

# Define control
force = cs.MX.sym('f', 3)
u = force

f_expl = cs.vertcat(vel,
              force / self.mass
             )
f_impl = z_d - f_expl

# Define parameters for references (these will be set at runtime)
z_ref = cs.MX.sym('z_ref', self.nz)
u_ref = cs.MX.sym('u_ref', self.nu)

model = AcadosModel()
model.f_impl_expr = f_impl
model.f_expl_expr = f_expl
model.x = z
model.xdot = z_d
model.u = u
model.p = cs.vertcat(z_ref, u_ref)  # Add parameters to model
model.name = self.name

ocp = AcadosOcp()
ocp.model = model

# set prediction horizon
ocp.solver_options.N_horizon = self.N
ocp.solver_options.tf = (self.N-1) * self.dh

# set cost information
ocp.cost.cost_type = `EXTERNAL` 
ocp.cost.cost_type_e = `EXTERNAL`  
ocp.cost.cost_type_0 = `EXTERNAL`  

# Add parameters to model
ocp.parameter_values =  np.concatenate((np.zeros(self.nz), np.zeros(self.nu)))

Although the cost I’m working with can be implemented using LINEAR_LS, I’m working my way up to adding quaternion and introducing nonlinear quaternion error costs. I assumed I only needed path-wise and terminal constraints to start:

# Path cost: tracking error for state and control
error = cs.vertcat(z - z_ref, u - u_ref)
ocp.cost.cost_expr_ext_cost = error.T @ self.W @ error

# Terminal cost: only state tracking (no control)
error_e = z - z_ref
ocp.cost.cost_expr_ext_cost_e = error_e.T @ self.Q @ error_e

And the rest of the OCP setup is boilerplate:

# set initial state
ocp.constraints.x0 = np.arange(self.nz)
ocp.constraints.idxbx0 = np.arange(self.nz)

# set actuator constraints
ocp.constraints.lbu = -self.Fmax*np.ones((self.nu))
ocp.constraints.ubu = self.Fmax*np.ones((self.nu))
ocp.constraints.idxbu = np.arange(self.nu)

# solve options
ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM'
ocp.solver_options.hessian_approx = 'GAUSS_NEWTON'
ocp.solver_options.integrator_type = 'ERK'
ocp.solver_options.nlp_solver_type = 'SQP'

ocp.solver_options.qp_solver_cond_N = self.N 

self.ocp_solver = AcadosOcpSolver(ocp, json_file='acados_ocp.json')
self.acados_integrator = AcadosSimSolver(ocp, json_file='acados_integrator.json')

However, when I actually get around to running this, I get the following error:

 File "/usr/local/lib/python3.10/dist-packages/acados_template/acados_ocp.py", line 897, in make_consistent
    self._make_consistent_cost_initial()
  File "/usr/local/lib/python3.10/dist-packages/acados_template/acados_ocp.py", line 237, in _make_consistent_cost_initial
    raise TypeError('cost_expr_ext_cost_0 should be casadi expression.')
TypeError: cost_expr_ext_cost_0 should be casadi expression.

I’ve tried setting ocp.cost.cost_expr_ext_cost_0 = 0.0 as a workaround, but this doesn’t seem to help. Any suggestions on what I might be doing wrong?

Hi :waving_hand:

Your are right, you do not need to set the cost at stage 0 explicitly. And it should all be working fine if you delete this line ocp.cost.cost_type_0 = EXTERNAL``

Best, Katrin

Ah, I was able to figure out the error! Commenting out ocp.cost.cost_type_0 = EXTERNAL didn’t seem to make the bug go away, so upon digging further, I realized the typo was in the lines:

# Path cost: tracking error for state and control
error = cs.vertcat(z - z_ref, u - u_ref)
ocp.cost.cost_expr_ext_cost = error.T @ self.W @ error

# Terminal cost: only state tracking (no control)
error_e = z - z_ref
ocp.cost.cost_expr_ext_cost_e = error_e.T @ self.Q @ error_e

These should be ocp.model.cost_expr_ext_cost and ocp.model.cost_expr_ext_cost_e, respectively. After making this fix and leaving ocp.cost.cost_type_0 = EXTERNAL commented out, the EXTERNAL cost function now compiles.

1 Like