Convex_over_nonlinear cost formulation

Hello,

I am working with acados in python and have a question regarding the formulation for the CONVEX_OVER_NONLINEAR cost formulation. I was previously using NONLINEAR_LS as discussed in neural-network-as-terminal-cost which allowed me to use a neural network as the terminal cost. However, due to some other pytorch/training related issues I have to move away from NONLINEAR_LS.

Basically, I still want to exploit the GAUSS_NEWTON approximation but without acados performing the least squares operation on the output of the neural network. I saw something similar suggested in this post and I think this also applies to me.

Previously, I fed V_\theta(x) as the cost_y_expr_e but now I am feeding f instead.
f = \frac{1}{2}(V_\theta(x))^2

This is my previous code for implementing the terminal cost with NONLINEAR_LS.

def define_terminal_cost(self, ocp, model, config):
    # Extract dims
    nx = model.x.rows()
    self.ny_e = self.ee_expr.shape[0]+ nx//2

    # Create parameters for goal, obstacle
    self.p = np.array(self.config["mpc"]["yref"])
    ocp.model.p = SX.sym('p', self.p.shape[0])  # Full yref as parameter
    ocp.parameter_values = np.zeros(self.p.shape[0])

    # Export trained NN model (It can be assumed that the exported model is V)
    self.l4c_model = export_torch_model(config, self.worker_id)
    # Set NN as y_expr_e
    y_sym = self.l4c_model(ca.transpose(vertcat(model.x, ocp.model.p)))
    ocp.model.cost_y_expr_e = y_sym

    # Set cost type, weights and yref
    ocp.cost.cost_type_e = 'NONLINEAR_LS'               # Terminal cost
    ocp.cost.W_e = np.eye(y_sym.shape[0])                      # Weights set to 1, meaning no scaling for the NN output
    ocp.cost.yref_e = np.zeros((y_sym.shape[0], ))                   # Set terminal reference to zero for NN output

And this is the new workflow for CONVEX_OVER_NONLINEAR

def define_terminal_cost(self, ocp, model, config):
    # Extract dims
    nx = model.x.rows()
    self.ny_e = self.ee_expr.shape[0]+ nx//2

    # Create parameters for goal, obstacle
    self.p = np.array(self.config["mpc"]["yref"])
    ocp.model.p = SX.sym('p', self.p.shape[0])  # Full yref as parameter
    ocp.parameter_values = np.zeros(self.p.shape[0])

    # Export trained NN model (It can be assumed that the exported model is f)
    self.l4c_model = export_torch_model(config, self.worker_id)

    # Set NN as y_expr_e
    x_aug = ca.transpose(ca.vertcat(model.x, ocp.model.p))
    y_sym = ca.transpose(self.l4c_model(x_aug))
    ocp.model.cost_y_expr_e = y_sym

    # Set cost type, weights and yref
    ocp.cost.cost_type_e = 'CONVEX_OVER_NONLINEAR'               # Terminal cost
    ocp.cost.yref_e = np.zeros((y_sym.shape[0], ))                   # Set terminal reference to zero for NN output
 
    r = ca.SX.sym("r")
    ocp.model.cost_r_in_psi_expr_e = r

    # identity convex function
    ocp.model.cost_psi_expr_e = r

I was wondering if I have implemented r and phi correctly?

Thank you for any help.
Nicodemus

Hi Nicodemus.

your implementation is correct. Note that you do not get any Hessian contribution from the terminal cost with this formulation, since the outer convex function is the identity which has zero curvature.

Best, Katrin

Hi Katrin,

Thanks for the verification.

I was thinking further about your comment about Hessian contribution and concluded that while I am trying to exploit the GAUSS_NETWON approximation and since there is no contribution from it, I might as well try the EXTERNAL cost type and change the ocp.solver_options.hessian_approx to EXACT or compute the GAUSS_NEWTON myself since the output of the neural network indeed satisfies the LS format.

I tried looking at acados/examples/acados_python/pendulum_on_cart/ocp/example_custom_hessian.py at main · acados/acados · GitHub and acados/examples/acados_python/pendulum_on_cart/ocp/ocp_example_cost_formulations.py at main · acados/acados · GitHub but did not see a conclusive example of how to implement the EXTERNALcost type. Any guidance would be much appreciated. This is what I have now,

    def define_terminal_cost(self, ocp, model, config):
        # Extract dims
        nx = model.x.rows()
        self.ny_e = self.ee_expr.shape[0]+ nx//2

        # Create parameters for goal, obstacle
        self.p = np.array(self.config["mpc"]["yref"])
        ocp.model.p = SX.sym('p', self.p.shape[0])  # Full yref as parameter
        ocp.parameter_values = np.zeros(self.p.shape[0])

        # Export trained NN model
        self.l4c_model = export_torch_model(config, self.worker_id)

        # Set NN as cost_expr_ext_cost_e
        x_aug = ca.transpose(ca.vertcat(model.x, ocp.model.p))
        y_sym = ca.transpose(self.l4c_model(x_aug))
        # ocp.model.cost_y_expr_e = y_sym
        ocp.model.cost_expr_ext_cost_e = y_sym

        # Set cost type, weights and yref
        ocp.cost.cost_type_e = "EXTERNAL"                                  # Terminal cost
        # ocp.cost.yref_e = np.zeros((y_sym.shape[0], ))                   # Set terminal reference to zero for NN output
        # ocp.model.cost_expr_ext_cost_custom_hess_e

        # Link shared library
        ocp.solver_options.model_external_shared_lib_dir = self.l4c_model.shared_lib_dir
        ocp.solver_options.model_external_shared_lib_name = self.l4c_model.name

Additionally, I also see that ocp.solver_options.hessian_approx does not have a _e hence does this mean that both stage and terminal need to adhere to the EXACT Hessian?

Thank you
Nico