Converting casadi opti syntax to acados python

I want to convert my casadi code to acados python and compare the computational time. I have several doubts in setting up acados.

1. Setting up states, controls, parameters and variables in acados:
a. I have defined my states and controls as:
self.x = self.opti.variable(self.nx, self.N + 1)
self.u = self.opti.variable(self.nu, self.N)
How do i do the same in acados.
I tried this in this way:
self.ocp = AcadosOcp()
self.ocp.model = AcadosModel()
self.ocp.model.name = ‘vehicle_running_acados’
self.ocp.model.x = self.vehicle.x
self.ocp.model.u = self.vehicle.u
I want to know if i can define my states and controls with dimensions seen in casadi way ( as my constraints formulated with this dimensions in mind)
b) How do i set up the variables and parameters like I did in casadi. Is there any equivalent syntax for this?
2. Setting up the constraints:
I’m using stachastic mpc and I have tighetened the bounds for every states:
for i in range(self.N+1):
self.opti.subject_to(self.x[:, i] <= DM(self.tightened_bound_N_list_up[i].reshape(-1, 1)))
self.opti.subject_to(self.x[:, i] >= DM(self.tightened_bound_N_list_lw[i].reshape(-1, 1)))
This means the constraints are different at each time steps. Usually in the examples provided in the acados repo, the constraints are one numerical value. Is there any option to make it in this way?
3. Cost:
I want to optimize my cost as well: I have defined this in this way in casadi:
def setCost(self):
“”"
Set cost function for the optimization problem.
“”"
L, Lf = self.vehicle.getCost()
cost=getTotalCost(L, Lf, self.x, self.u, self.refx, self.refu, self.N)
# Add slack variable cost
cost += 3e4self.lambda_s@ self.lambda_s.T
for i in range(self.N+1):
cost += self.sigma[0,i]
for i in range(self.N-1):
cost += 1e2
(self.u[1,i+1]-self.u[1,i])@(self.u[1,i+1]-self.u[1,i]).T
self.cost=cost
# Add slack variable cost for y
# cost += 5e5*self.slack_y@ self.slack_y.T
self.opti.minimize(self.cost)
I’m not sure how do we do this in acados.

Hi! :wave:

in acados, the OCP problem is defined in continuous time and acados will take care of discretizing your problem to a multiple shooting formulation.

Please check the problem formulation, as well as the minimal example.

If I understand correctly, you would like to change the lower and upper bounds on the states for each shooting node. This needs to be done after solver creation via acados_solver.constraints_set(stage, "lbx", lbx) for the lower bound and acados_solver.constraints_set(stage, "ubx", ubx) for the upper bound.

I hope this is helpful!

hello, I tried to follow your way “acados_solver.constraints_set(stage, “ubx”, ubx)” to define dynamic constraints, but it seems that the constraints here is always np.array([2000, 2000, 5 .1, 1])…or , could you tell me is there any other way to define dynamic constraints?

User Questions

for i in range(self.N):

  start = timeit.default_timer()

  self.solver.constraints_set(0, 'lbx', x_current)

  self.solver.constraints_set(0, 'ubx', x_current)

        for j in range(N):
            dynamic_ubx = np.array([2000, 2000, 5 + j*0.1, 1])  # Dynamic upper bound for states
            self.solver.constraints_set(j, 'ubx', dynamic_ubx)
            print("dynamic_ubx is:", dynamic_ubx)
  
  
        status = self.solver.solve()
  
        if status != 0 :
            raise Exception('acados acados_ocp_solver returned status {}. Exiting.'.format(status))
  
        simU[i, :] = self.solver.get(0, 'u')
        #! get total X
        cost_value = self.solver.get_cost()
        print("Optimization cost:", cost_value)
        time_record[i] =  timeit.default_timer() - start
  
        # simulate system
        self.integrator.set('x', x_current)
        self.integrator.set('u', simU[i, :])
  
        status_s = self.integrator.solve()
        if status_s != 0:
            raise Exception('acados integrator returned status {}. Exiting.'.format(status))
  
        # updated
        x_current = self.integrator.get('x')
        # print("X_current is:", i, x_current)
        
        simX[i+1, :] = x_current

Hi :wave:

I guess you want the for loop to start at index 1. At the moment you are overwriting the initial state constraint self.solver.constraints_set(0, 'ubx', x_current) within the for loop.
Besides, it’s enough to set the constraints only once outside the simulation loop (here with index i) and only update the initial state constraint within the loop.

Apart from that the code looks good to me.

thanks !
I have another question, if i want to define the constraint like this
“self.opti.subject_to(self.x[0,:] <= self.S(self.lead) + self.traffic_slack[0,:]-T * self.x[2,:])”

where self.x is opti.variable, how should i define this parametric constraint in acados…it seems a bit difficult to set it using self.solver.constraints_set

For linear constraints you need to set D and C as is done in this example:

After solver creation you can again change the values of lg and ug via constraints_set