Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/acados/acados
Browse files Browse the repository at this point in the history
  • Loading branch information
Andrea Zanelli committed Jun 17, 2024
2 parents 4cc423a + 3e91fb8 commit 74f8aa5
Show file tree
Hide file tree
Showing 7 changed files with 26 additions and 15 deletions.
1 change: 1 addition & 0 deletions acados/ocp_nlp/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ OBJS += ocp_nlp_dynamics_common.o
OBJS += ocp_nlp_dynamics_cont.o
OBJS += ocp_nlp_dynamics_disc.o
OBJS += ocp_nlp_sqp.o
OBJS += ocp_nlp_ddp.o
OBJS += ocp_nlp_sqp_rti.o
OBJS += ocp_nlp_reg_common.o
OBJS += ocp_nlp_reg_convexify.o
Expand Down
5 changes: 3 additions & 2 deletions docs/installation/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@ git submodule update --recursive --init
```

### Build and install `acados`
Both a CMake and a Makefile based build system is supported at the moment.
A CMake and a Makefile based build system is available in acados.
Note that only the `CMake` build system is tested using CI and is thus recommended.
Please choose one and proceed with the corresponding paragraph.

#### **CMake**
#### **CMake** (recommended)
Install `acados` as follows:
```
mkdir -p build
Expand Down
20 changes: 13 additions & 7 deletions examples/acados_python/getting_started/minimal_example_ocp.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
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

def main():
Expand All @@ -52,16 +53,21 @@ def main():
# set prediction horizon
ocp.solver_options.tf = Tf

# set cost
# cost matrices
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
# 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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ def ellipsoid_surface_2D(P, n=100):
return a


def plot_trajectory(cfg: MPCParam, traj_ref:np.ndarray, traj_zo:np.ndarray, P_matrices=None):
def plot_trajectory(cfg: MPCParam, traj_ref:np.ndarray, traj_zo:np.ndarray, P_matrices=None, closed_loop=True):

fig = plt.figure(1)
ax = fig.add_subplot(1,1,1)
Expand All @@ -160,12 +160,14 @@ def plot_trajectory(cfg: MPCParam, traj_ref:np.ndarray, traj_zo:np.ndarray, P_ma

ax.set_xlabel("x [m]")
ax.set_ylabel("y [m]")
ax.set_xticks(np.arange(-2., 9., 2.))
ax.set_yticks(np.arange(0., 5., 2.))
ax.set_ylim([-.5, 3.6])
if closed_loop:
ax.set_xticks(np.arange(-2., 9., 2.))
ax.set_yticks(np.arange(0., 5., 2.))
ax.set_ylim([-.5, 3.6])
ax.set_aspect("equal")
ax.legend()
plt.tight_layout()
plt.grid()
if not os.path.exists("figures"):
os.makedirs("figures")

Expand Down
2 changes: 1 addition & 1 deletion examples/acados_python/zoRO_example/diff_drive/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ def solve_single_zoro_problem_visualize_uncertainty():
print(f"x_opt = {x_opt}")
print(f"status = {status}")
plot_trajectory(cfg_zo, x_ref_interp, x_opt,
P_matrices=zoroMPC.ocp.zoro_description.backoff_scaling_gamma**2 * zoroMPC.P_mats)
P_matrices=zoroMPC.ocp.zoro_description.backoff_scaling_gamma**2 * zoroMPC.P_mats, closed_loop=False)


def plot_result_trajectory(n_executions: int, use_custom_update=True):
Expand Down
2 changes: 1 addition & 1 deletion interfaces/acados_template/acados_template/acados_ocp.py
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ def make_consistent(self) -> None:
if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess_0 is None:
print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n"
"got cost_type_0: EXTERNAL, hessian_approx: 'GAUSS_NEWTON.'\n"
"GAUSS_NEWTON hessian is only supported for cost_types [NON]LINEAR_LS.\n"
"GAUSS_NEWTON hessian is not defined for EXTERNAL cost formulation.\n"
"If you continue, acados will proceed computing the exact hessian for the cost term.\n"
"Note: There is also the option to use the external cost module with a numerical hessian approximation (see `ext_cost_num_hess`).\n"
"OR the option to provide a symbolic custom hessian approximation (see `cost_expr_ext_cost_custom_hess`).\n")
Expand Down
1 change: 1 addition & 0 deletions interfaces/acados_template/acados_template/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
'3.6.2',
'3.6.3',
'3.6.4',
'3.6.5',
)

TERA_VERSION = "0.0.34"
Expand Down

0 comments on commit 74f8aa5

Please sign in to comment.