Skip to content

Commit cf4991b

Browse files
committed
OCP result diagnostics
- more unit tests (TCP + direct iface) - opengen v0.10.0a2 - remove unnecessary log msg from low-level builder - OcpSolution: number formatting - website docs
1 parent 4af506e commit cf4991b

5 files changed

Lines changed: 195 additions & 13 deletions

File tree

docs/python-ocp.md

Lines changed: 59 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,30 @@ description: Optimal Control with OpEn/opengen
66

77
<script type="text/x-mathjax-config">MathJax.Hub.Config({tex2jax: {inlineMath: [['$','$'], ['\\(','\\)']]}});</script>
88
<script type="text/javascript" async src="https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.1/MathJax.js?config=TeX-AMS-MML_HTMLorMML"></script>
9+
<style>
10+
.but{
11+
border: none;
12+
color: #348c4f;
13+
padding: 15px 20px;
14+
text-align: center;
15+
text-decoration: none;
16+
display: inline-block;
17+
font-size: 16px;
18+
margin: 0px 0px;
19+
cursor: pointer;
20+
width: 250px;
21+
border-radius: 8px;
22+
}
23+
</style>
24+
<style>
25+
.but1 {
26+
background-color: #e9e642;
27+
}
28+
</style><style>
29+
.but2 {
30+
background-color: #008CBA;
31+
}
32+
</style>
933

1034
<div class="alert alert-warning">
1135
<b>Info:</b> The functionality presented here was introduced in <code>opengen</code> version <code>0.10.0a1</code>.
@@ -17,6 +41,8 @@ of optimal control problems. In an intuitive and straightforward way,
1741
the user defines the problem ingredients (stage/terminal costs,
1842
state/input constraints, dynamics).
1943

44+
<a href="https://colab.research.google.com/drive/17vbVUbqcah9seIg17aN6bW0-T15FWrBo?usp=sharing" target="_blank"><button class="but but1" ><b>Try this on Google Colab</b></button></a>
45+
2046
## In a nutshell: quick overview
2147

2248
Suppose you want to solve the optimal control problem
@@ -25,9 +51,9 @@ Suppose you want to solve the optimal control problem
2551
\begin{align}
2652
\mathbb{P}_N(p){}:{}\operatorname*{Minimize}_{u_0, \ldots, u_{N-1}}&
2753
\sum_{t=1}^{N - 1}
28-
\underbrace{\|x_t-x^{\mathrm{ref}}\|^2 + r \|u_t\|^2}_{\text{stage cost}}
54+
\underbrace{q\|x_t-x^{\mathrm{ref}}\|^2 + r \|u_t\|^2}_{\text{stage cost}}
2955
+
30-
\underbrace{\|x_N-x^{\mathrm{ref}}\|^2}_{\text{terminal cost}}
56+
\underbrace{10\|x_N-x^{\mathrm{ref}}\|^2}_{\text{terminal cost}}
3157
\\
3258
\text{subject to: }& x_{t+1} = F(x_t, u_t), t=0,\ldots, N-1
3359
\\
@@ -38,6 +64,37 @@ Suppose you want to solve the optimal control problem
3864
&x_0=x
3965
\end{align}
4066
\]</div>
67+
Suppose the state is two-dimensional and the input is one-dimensional.
68+
The dynamics is
69+
<div class="math">
70+
\[
71+
\begin{align}
72+
F(x, u; a) =
73+
\begin{bmatrix}
74+
ax_1 + 0.2x_1^2 - 1.2 x_2 + u \\
75+
\sin(x_2) + 0.2 x_1^3 - u
76+
\end{bmatrix},
77+
\end{align}
78+
\]</div>
79+
where $a$ is a constant parameter. Suppose the stage cost
80+
function is
81+
<div class="math">
82+
\[
83+
\begin{align}
84+
\ell(x, u; x^{\rm ref}, q, r)
85+
{}={}
86+
q\| x - x^{\rm ref}\|^2 + r \|u\|^2,
87+
\end{align}
88+
\]</div>
89+
where $x^{\rm ref}$, $q$, and $r$ are parameters. The terminal
90+
cost function is
91+
<div class="math">
92+
\[
93+
\begin{align}
94+
V_f(x; x^{\mathrm{ref}}) = 10\|x_N-x^{\mathrm{ref}}\|^2.
95+
\end{align}
96+
\]</div>
97+
Lastly, we
4198
This can be done as follows:
4299

43100
```python

open-codegen/VERSION

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
0.10.0a1
1+
0.10.0a2

open-codegen/opengen/builder/optimizer_builder.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -659,7 +659,6 @@ def __check_user_provided_parameters(self):
659659
"For now we only support orthans (e.g., F1(u, p) <= 0).")
660660

661661
def __generate_code_python_bindings(self):
662-
self.__logger.info("Generating code for Python bindings")
663662
target_dir = self.__target_dir()
664663
python_bindings_dir_name = _PYTHON_BINDINGS_PREFIX + self.__meta.optimizer_name
665664
python_bindings_dir = os.path.join(

open-codegen/opengen/ocp/solution.py

Lines changed: 35 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
"""High-level solution objects returned by OCP-generated optimizers."""
22

3+
from numbers import Real
4+
35
class OcpSolution:
46
"""High-level solution returned by :meth:`GeneratedOptimizer.solve`.
57
@@ -21,19 +23,46 @@ def __init__(self, raw, inputs, states):
2123
self.cost = getattr(raw, "cost", None)
2224
self.exit_status = getattr(raw, "exit_status", None)
2325
self.solve_time_ms = getattr(raw, "solve_time_ms", None)
26+
self.penalty = getattr(raw, "penalty", None)
27+
self.num_outer_iterations = getattr(raw, "num_outer_iterations", None)
28+
self.num_inner_iterations = getattr(raw, "num_inner_iterations", None)
29+
self.last_problem_norm_fpr = getattr(raw, "last_problem_norm_fpr", None)
30+
self.f1_infeasibility = getattr(raw, "f1_infeasibility", None)
31+
self.f2_norm = getattr(raw, "f2_norm", None)
2432
self.lagrange_multipliers = getattr(raw, "lagrange_multipliers", None)
2533

2634
def __repr__(self):
2735
"""Return a readable multi-line summary of the solution."""
36+
def fmt(value):
37+
if isinstance(value, bool):
38+
return str(value)
39+
if isinstance(value, Real):
40+
numeric = float(value)
41+
if numeric == 0.0:
42+
return "0.0"
43+
text = f"{numeric:.4g}"
44+
return "0.0" if text == "-0" else text
45+
if isinstance(value, list):
46+
return "[" + ", ".join(fmt(item) for item in value) + "]"
47+
if isinstance(value, tuple):
48+
return "(" + ", ".join(fmt(item) for item in value) + ")"
49+
return str(value)
50+
2851
return "\n".join([
2952
"OCP Solution:",
3053
f" Exit status.......... {self.exit_status}",
31-
f" Cost................. {self.cost}",
32-
f" Solve time [ms]...... {self.solve_time_ms}",
33-
f" Decision variables... {self.solution}",
34-
f" Inputs............... {self.inputs}",
35-
f" States............... {self.states}",
36-
f" Lagrange multipliers. {self.lagrange_multipliers}",
54+
f" Cost................. {fmt(self.cost)}",
55+
f" Solve time [ms]...... {fmt(self.solve_time_ms)}",
56+
f" Penalty.............. {fmt(self.penalty)}",
57+
f" Outer iterations..... {fmt(self.num_outer_iterations)}",
58+
f" Inner iterations..... {fmt(self.num_inner_iterations)}",
59+
f" FPR.................. {fmt(self.last_problem_norm_fpr)}",
60+
f" ALM infeasibility.... {fmt(self.f1_infeasibility)}",
61+
f" PM infeasibility..... {fmt(self.f2_norm)}",
62+
f" Decision variables... {fmt(self.solution)}",
63+
f" Inputs............... {fmt(self.inputs)}",
64+
f" States............... {fmt(self.states)}",
65+
f" Lagrange multipliers. {fmt(self.lagrange_multipliers)}",
3766
])
3867

3968
__str__ = __repr__

open-codegen/test/test_ocp.py

Lines changed: 100 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,12 @@ def __init__(self, solution):
1212
self.cost = 1.23
1313
self.exit_status = "Converged"
1414
self.solve_time_ms = 0.7
15+
self.penalty = 12.5
16+
self.num_outer_iterations = 3
17+
self.num_inner_iterations = 27
18+
self.last_problem_norm_fpr = 1e-6
19+
self.f1_infeasibility = 2e-5
20+
self.f2_norm = 3e-5
1521
self.lagrange_multipliers = []
1622

1723

@@ -71,7 +77,6 @@ def setUpOCP1(cls):
7177
.with_max_inner_iterations(500)
7278
.with_max_outer_iterations(10),
7379
).build()
74-
cls.ocp1_optimizer.save()
7580
cls.ocp1_manifest_path = os.path.join(cls.ocp1_optimizer.target_dir, "optimizer_manifest.json")
7681
cls.ocp1_rollout_path = os.path.join(cls.ocp1_optimizer.target_dir, "rollout.casadi")
7782

@@ -132,8 +137,6 @@ def make_problem(shooting):
132137
solver_configuration=solver_config,
133138
).build()
134139

135-
cls.ocp2_single_optimizer.save()
136-
cls.ocp2_multiple_optimizer.save()
137140
cls.ocp2_single_manifest_path = os.path.join(
138141
cls.ocp2_single_optimizer.target_dir, "optimizer_manifest.json")
139142
cls.ocp2_multiple_manifest_path = os.path.join(
@@ -325,10 +328,46 @@ def test_multistep_rk4_codegen(self):
325328
initial_guess=[0.0] * 5,
326329
)
327330

331+
# Check the result has all necessary attributes
332+
self.assertTrue(hasattr(result, "raw"))
333+
self.assertTrue(hasattr(result, "solution"))
334+
self.assertTrue(hasattr(result, "inputs"))
335+
self.assertTrue(hasattr(result, "states"))
336+
self.assertTrue(hasattr(result, "cost"))
337+
self.assertTrue(hasattr(result, "exit_status"))
338+
self.assertTrue(hasattr(result, "solve_time_ms"))
339+
self.assertTrue(hasattr(result, "penalty"))
340+
self.assertTrue(hasattr(result, "num_outer_iterations"))
341+
self.assertTrue(hasattr(result, "num_inner_iterations"))
342+
self.assertTrue(hasattr(result, "last_problem_norm_fpr"))
343+
self.assertTrue(hasattr(result, "f1_infeasibility"))
344+
self.assertTrue(hasattr(result, "f2_norm"))
345+
self.assertTrue(hasattr(result, "lagrange_multipliers"))
346+
347+
# Check all attributes of `result`
328348
self.assertEqual("Converged", result.exit_status)
349+
self.assertIsInstance(result.solution, list)
350+
self.assertIsInstance(result.inputs, list)
351+
self.assertIsInstance(result.states, list)
329352
self.assertEqual(5, len(result.solution))
330353
self.assertEqual(5, len(result.inputs))
331354
self.assertEqual(6, len(result.states))
355+
self.assertIsInstance(result.cost, float)
356+
self.assertGreaterEqual(result.cost, 0.0)
357+
self.assertIsInstance(result.solve_time_ms, float)
358+
self.assertGreater(result.solve_time_ms, 0.0)
359+
self.assertIsInstance(result.penalty, float)
360+
self.assertIsInstance(result.num_outer_iterations, int)
361+
self.assertGreaterEqual(result.num_outer_iterations, 1)
362+
self.assertIsInstance(result.num_inner_iterations, int)
363+
self.assertGreaterEqual(result.num_inner_iterations, 1)
364+
self.assertIsInstance(result.last_problem_norm_fpr, float)
365+
self.assertGreaterEqual(result.last_problem_norm_fpr, 0.0)
366+
self.assertIsInstance(result.f1_infeasibility, float)
367+
self.assertGreaterEqual(result.f1_infeasibility, 0.0)
368+
self.assertIsInstance(result.f2_norm, float)
369+
self.assertGreaterEqual(result.f2_norm, 0.0)
370+
self.assertIsInstance(result.lagrange_multipliers, list)
332371
self.assertAlmostEqual(result.states[0][0], 1.0)
333372
self.assertAlmostEqual(result.states[0][1], 0.0)
334373

@@ -421,6 +460,12 @@ def test_generated_optimizer_defaults(self):
421460
self.assertEqual(result.states[0], [0.0, 0.0])
422461
self.assertAlmostEqual(result.states[-1][0], 0.6)
423462
self.assertAlmostEqual(result.states[-1][1], -0.6)
463+
self.assertEqual(result.penalty, 12.5)
464+
self.assertEqual(result.num_outer_iterations, 3)
465+
self.assertEqual(result.num_inner_iterations, 27)
466+
self.assertEqual(result.last_problem_norm_fpr, 1e-6)
467+
self.assertEqual(result.f1_infeasibility, 2e-5)
468+
self.assertEqual(result.f2_norm, 3e-5)
424469

425470
def test_optimizer_manifest_roundtrip(self):
426471
manifest_path = self.ocp1_manifest_path
@@ -521,6 +566,58 @@ def test_multiple_shooting_state_extraction(self):
521566
self.assertEqual(result.inputs, [[0.1], [0.2], [0.4]])
522567
self.assertEqual(result.states, [[0.0, 0.0], [0.1, -0.1], [0.3, -0.3], [0.7, -0.7]])
523568

569+
def test_tcp_optimizer_result(self):
570+
optimizer = og.ocp.GeneratedOptimizer.load(self.ocp2_single_manifest_path)
571+
572+
try:
573+
result = optimizer.solve(
574+
x0=[1.0, -1.0],
575+
xref=[0.0, 0.0],
576+
)
577+
578+
self.assertTrue(hasattr(result, "raw"))
579+
self.assertTrue(hasattr(result, "solution"))
580+
self.assertTrue(hasattr(result, "inputs"))
581+
self.assertTrue(hasattr(result, "states"))
582+
self.assertTrue(hasattr(result, "cost"))
583+
self.assertTrue(hasattr(result, "exit_status"))
584+
self.assertTrue(hasattr(result, "solve_time_ms"))
585+
self.assertTrue(hasattr(result, "penalty"))
586+
self.assertTrue(hasattr(result, "num_outer_iterations"))
587+
self.assertTrue(hasattr(result, "num_inner_iterations"))
588+
self.assertTrue(hasattr(result, "last_problem_norm_fpr"))
589+
self.assertTrue(hasattr(result, "f1_infeasibility"))
590+
self.assertTrue(hasattr(result, "f2_norm"))
591+
self.assertTrue(hasattr(result, "lagrange_multipliers"))
592+
593+
self.assertEqual("Converged", result.exit_status)
594+
self.assertIsInstance(result.solution, list)
595+
self.assertIsInstance(result.inputs, list)
596+
self.assertIsInstance(result.states, list)
597+
self.assertEqual(5, len(result.inputs))
598+
self.assertEqual(6, len(result.states))
599+
self.assertIsInstance(result.cost, float)
600+
self.assertGreaterEqual(result.cost, 0.0)
601+
self.assertIsInstance(result.solve_time_ms, float)
602+
self.assertGreater(result.solve_time_ms, 0.0)
603+
self.assertIsInstance(result.penalty, float)
604+
self.assertGreater(result.penalty, 0.0)
605+
self.assertIsInstance(result.num_outer_iterations, int)
606+
self.assertGreaterEqual(result.num_outer_iterations, 1)
607+
self.assertIsInstance(result.num_inner_iterations, int)
608+
self.assertGreaterEqual(result.num_inner_iterations, 1)
609+
self.assertIsInstance(result.last_problem_norm_fpr, float)
610+
self.assertGreaterEqual(result.last_problem_norm_fpr, 0.0)
611+
self.assertIsInstance(result.f1_infeasibility, float)
612+
self.assertGreaterEqual(result.f1_infeasibility, 0.0)
613+
self.assertIsInstance(result.f2_norm, float)
614+
self.assertGreaterEqual(result.f2_norm, 0.0)
615+
self.assertIsInstance(result.lagrange_multipliers, list)
616+
self.assertAlmostEqual(result.states[0][0], 1.0)
617+
self.assertAlmostEqual(result.states[0][1], -1.0)
618+
finally:
619+
optimizer.kill()
620+
524621
def test_single_vs_multiple(self):
525622
single_optimizer = og.ocp.GeneratedOptimizer.load(self.ocp2_single_manifest_path)
526623
multiple_optimizer = og.ocp.GeneratedOptimizer.load(self.ocp2_multiple_manifest_path)

0 commit comments

Comments
 (0)