Indeed Andrea, the envs are different, thanks for pointing this out.
I managed to run the example on colab cells, but needed to use ctypes to load all .so files needed when calling AcadosOcpSolver()
maybe reflecting the same env in shell / colab notebook cells will lead to a more elegant solution and easier to run acados on colab. I’ll try to work on this
below is the code to run on colab as mentioned (simply pasting in a cell and run will reproduce):
!git clone https://github.com/acados/acados.git
%cd acados
!git submodule update --recursive --init
%mkdir -p build
%cd /content/acados/build
!cmake -DACADOS_WITH_QPOASES=ON ..
!make install -j4
%pip install -e /content/acados/interfaces/acados_template
# below is needed for running the minimal_example_ocp.py, so that tera is installed
import os
os.environ['LD_LIBRARY_PATH']='/usr/local/nvidia/lib:/usr/local/nvidia/lib64:/content/acados/lib'
os.environ['ACADOS_SOURCE_DIR']='/content/acados'
%cd /content/acados/examples/acados_python/getting_started/
!echo "y" | /usr/bin/python3 minimal_example_ocp.py
import sys
sys.path.append("/content/acados/interfaces/acados_template") # necessary so colab knows where to find acados_template
from acados_template import AcadosOcp, AcadosOcpSolver
from pendulum_model import export_pendulum_ode_model
import numpy as np
import casadi as ca
from utils import plot_pendulum
import ctypes # necessary so colab knows where to find *.so files
ctypes.cdll.LoadLibrary('/content/acados/lib/libqpOASES_e.so')
ctypes.cdll.LoadLibrary('/content/acados/lib/libblasfeo.so')
ctypes.cdll.LoadLibrary('/content/acados/lib/libhpipm.so')
#### example code begins
# create ocp object to formulate the OCP
ocp = AcadosOcp()
# set model
model = export_pendulum_ode_model()
ocp.model = model
Tf = 1.0
nx = model.x.rows()
nu = model.u.rows()
N = 20
# set prediction horizon
ocp.solver_options.N_horizon = N
ocp.solver_options.tf = Tf
# cost matrices
Q_mat = 2*np.diag([1e3, 1e3, 1e-2, 1e-2])
R_mat = 2*np.diag([1e-2])
# path cost
ocp.cost.cost_type = 'NONLINEAR_LS'
ocp.model.cost_y_expr = ca.vertcat(model.x, model.u)
ocp.cost.yref = np.zeros((nx+nu,))
ocp.cost.W = ca.diagcat(Q_mat, R_mat).full()
# terminal cost
ocp.cost.cost_type_e = 'NONLINEAR_LS'
ocp.cost.yref_e = np.zeros((nx,))
ocp.model.cost_y_expr_e = model.x
ocp.cost.W_e = Q_mat
# set constraints
Fmax = 80
ocp.constraints.lbu = np.array([-Fmax])
ocp.constraints.ubu = np.array([+Fmax])
ocp.constraints.idxbu = np.array([0])
ocp.constraints.x0 = np.array([0.0, np.pi, 0.0, 0.0])
# set options
ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' # FULL_CONDENSING_QPOASES
# PARTIAL_CONDENSING_HPIPM, FULL_CONDENSING_QPOASES, FULL_CONDENSING_HPIPM,
# PARTIAL_CONDENSING_QPDUNES, PARTIAL_CONDENSING_OSQP, FULL_CONDENSING_DAQP
ocp.solver_options.hessian_approx = 'GAUSS_NEWTON' # 'GAUSS_NEWTON', 'EXACT'
ocp.solver_options.integrator_type = 'IRK'
# ocp.solver_options.print_level = 1
ocp.solver_options.nlp_solver_type = 'SQP' # SQP_RTI, SQP
ocp.solver_options.globalization = 'MERIT_BACKTRACKING' # turns on globalization
ocp_solver = AcadosOcpSolver(ocp)
simX = np.zeros((N+1, nx))
simU = np.zeros((N, nu))
status = ocp_solver.solve()
ocp_solver.print_statistics() # encapsulates: stat = ocp_solver.get_stats("statistics")
if status != 0:
raise Exception(f'acados returned status {status}.')
# get solution
for i in range(N):
simX[i,:] = ocp_solver.get(i, "x")
simU[i,:] = ocp_solver.get(i, "u")
simX[N,:] = ocp_solver.get(N, "x")
plot_pendulum(np.linspace(0, Tf, N+1), Fmax, simU, simX, latexify=True, time_label=model.t_label, x_labels=model.x_labels, u_labels=model.u_labels)