Hi
When I run the cartpole example in acados/examples/acados_python/getting_started/minimal_example_ocp.py, I get the following sequence of QP iterations per SQP iteration (I get these from solver.get_stats(‘qp_iter’)):
[ 0, 8, 26, 19, 13, 9, 4, 3, 3, 3, 3]
However, if I change ocp.solver_options.nlp_solver_type from ‘SQP’ to ‘SQP_RTI’, then run 10 iterations of real-time iteration, I get the following sequences of QP iterations:
[ 8, 28, 19, 13, 10, 4, 3, 3, 3, 3]
Why should these sequences be different? Is there a difference in the QP solved in the SQP_RTI version? I pasted the modified code below if it helps:
Thanks,
Anoop
This is the code from acados/examples/acados_python/getting_started/minimal_example_ocp.py, where the only modification is to print out an array of QP iterations so I can easily copy-paste it.
from acados_template import AcadosOcp, AcadosOcpSolver
from pendulum_model import export_pendulum_ode_model
import numpy as np
from utils import plot_pendulum
def main():
# 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.size()[0]
nu = model.u.size()[0]
N = 20
# set dimensions
ocp.dims.N = N
# set cost
Q_mat = 2*np.diag([1e3, 1e3, 1e-2, 1e-2])
R_mat = 2*np.diag([1e-2])
# the 'EXTERNAL' cost type can be used to define general cost terms
# NOTE: This leads to additional (exact) hessian contributions when using GAUSS_NEWTON hessian.
ocp.cost.cost_type = 'EXTERNAL'
ocp.cost.cost_type_e = 'EXTERNAL'
ocp.model.cost_expr_ext_cost = model.x.T @ Q_mat @ model.x + model.u.T @ R_mat @ model.u
ocp.model.cost_expr_ext_cost_e = model.x.T @ Q_mat @ model.x
# 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
# set prediction horizon
ocp.solver_options.tf = Tf
ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json')
simX = np.ndarray((N+1, nx))
simU = np.ndarray((N, nu))
status = ocp_solver.solve()
ocp_solver.print_statistics() # encapsulates: stat = ocp_solver.get_stats("statistics")
print(repr(np.array(ocp_solver.get_stats('qp_iter')).astype(np.int64)))
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=False)
if __name__ == '__main__':
main()
This is the version modified to use SQP_RTI:
from acados_template import AcadosOcp, AcadosOcpSolver
from pendulum_model import export_pendulum_ode_model
import numpy as np
from utils import plot_pendulum
def main():
# 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.size()[0]
nu = model.u.size()[0]
N = 20
# set dimensions
ocp.dims.N = N
# set cost
Q_mat = 2*np.diag([1e3, 1e3, 1e-2, 1e-2])
R_mat = 2*np.diag([1e-2])
# the 'EXTERNAL' cost type can be used to define general cost terms
# NOTE: This leads to additional (exact) hessian contributions when using GAUSS_NEWTON hessian.
ocp.cost.cost_type = 'EXTERNAL'
ocp.cost.cost_type_e = 'EXTERNAL'
ocp.model.cost_expr_ext_cost = model.x.T @ Q_mat @ model.x + model.u.T @ R_mat @ model.u
ocp.model.cost_expr_ext_cost_e = model.x.T @ Q_mat @ model.x
# 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_RTI' # SQP_RTI, SQP
# set prediction horizon
ocp.solver_options.tf = Tf
ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json')
simX = np.ndarray((N+1, nx))
simU = np.ndarray((N, nu))
qp_iter = []
for i in range(10):
status = ocp_solver.solve()
qp_iter.append(ocp_solver.get_stats('qp_iter')[1])
print(repr(np.array(qp_iter).astype(np.int64)))
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=False)
if __name__ == '__main__':
main()