|
| 1 | +import json |
1 | 2 | import os |
2 | 3 | import unittest |
3 | 4 |
|
@@ -38,11 +39,110 @@ def get_open_local_absolute_path(): |
38 | 39 |
|
39 | 40 | @classmethod |
40 | 41 | def setUpOCP1(cls): |
41 | | - pass |
| 42 | + optimizer_name = "ocp_manifest_bindings" |
| 43 | + ocp = og.ocp.OptimalControlProblem(nx=2, nu=1, horizon=3) |
| 44 | + ocp.add_parameter("x0", 2) |
| 45 | + ocp.add_parameter("xref", 2, default=[0.0, 0.0]) |
| 46 | + ocp.add_parameter("q", 1, default=1) |
| 47 | + ocp.add_parameter("r", 1, default=0.1) |
| 48 | + ocp.with_dynamics(lambda x, u, param: cs.vertcat(x[0] + u[0], x[1] - u[0])) |
| 49 | + ocp.with_stage_cost( |
| 50 | + lambda x, u, param, _t: |
| 51 | + param["q"] * cs.dot(x - param["xref"], x - param["xref"]) + param["r"] * cs.dot(u, u) |
| 52 | + ) |
| 53 | + ocp.with_terminal_cost( |
| 54 | + lambda x, param: cs.dot(x - param["xref"], x - param["xref"]) |
| 55 | + ) |
| 56 | + ocp.with_input_constraints(og.constraints.Rectangle([-1.0], [1.0])) |
| 57 | + |
| 58 | + cls.ocp1_optimizer = og.ocp.OCPBuilder( |
| 59 | + ocp, |
| 60 | + metadata=og.config.OptimizerMeta().with_optimizer_name(optimizer_name), |
| 61 | + build_configuration=og.config.BuildConfiguration() |
| 62 | + .with_open_version(local_path=OcpTestCase.get_open_local_absolute_path()) |
| 63 | + .with_build_directory(OcpTestCase.TEST_DIR) |
| 64 | + .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) |
| 65 | + .with_build_python_bindings(), |
| 66 | + solver_configuration=og.config.SolverConfiguration() |
| 67 | + .with_tolerance(1e-5) |
| 68 | + .with_delta_tolerance(1e-5) |
| 69 | + .with_initial_penalty(10.0) |
| 70 | + .with_penalty_weight_update_factor(1.2) |
| 71 | + .with_max_inner_iterations(500) |
| 72 | + .with_max_outer_iterations(10), |
| 73 | + ).build() |
| 74 | + cls.ocp1_optimizer.save() |
| 75 | + cls.ocp1_manifest_path = os.path.join(cls.ocp1_optimizer.target_dir, "optimizer_manifest.json") |
| 76 | + cls.ocp1_rollout_path = os.path.join(cls.ocp1_optimizer.target_dir, "rollout.casadi") |
42 | 77 |
|
43 | 78 | @classmethod |
44 | 79 | def setUpOCP2(cls): |
45 | | - pass |
| 80 | + def make_problem(shooting): |
| 81 | + ocp = og.ocp.OptimalControlProblem(nx=2, nu=1, horizon=5, shooting=shooting) |
| 82 | + ocp.add_parameter("x0", 2) |
| 83 | + ocp.add_parameter("xref", 2, default=[0.0, 0.0]) |
| 84 | + ocp.with_dynamics(lambda x, u, param: |
| 85 | + cs.vertcat(x[0] + u[0], x[1] - u[0])) |
| 86 | + ocp.with_stage_cost( |
| 87 | + lambda x, u, param, _t: |
| 88 | + cs.dot(x - param["xref"], x - param["xref"]) + 0.01 * cs.dot(u, u) |
| 89 | + ) |
| 90 | + ocp.with_terminal_cost( |
| 91 | + lambda x, param: |
| 92 | + 2.0 * cs.dot(x - param["xref"], x - param["xref"]) |
| 93 | + ) |
| 94 | + ocp.with_input_constraints(og.constraints.Rectangle([-0.4], [0.4])) |
| 95 | + ocp.with_path_constraint( |
| 96 | + lambda x, u, param, _t: cs.fmax(0.0, x[0] - 1.5) |
| 97 | + ) |
| 98 | + if shooting == og.ocp.ShootingMethod.MULTIPLE: |
| 99 | + ocp.with_dynamics_constraints("alm") |
| 100 | + return ocp |
| 101 | + |
| 102 | + solver_config = og.config.SolverConfiguration() \ |
| 103 | + .with_tolerance(1e-5) \ |
| 104 | + .with_delta_tolerance(1e-5) \ |
| 105 | + .with_initial_penalty(10.0) \ |
| 106 | + .with_penalty_weight_update_factor(1.2) \ |
| 107 | + .with_max_inner_iterations(5000) \ |
| 108 | + .with_max_outer_iterations(20) |
| 109 | + |
| 110 | + cls.ocp2_single_optimizer = og.ocp.OCPBuilder( |
| 111 | + make_problem(og.ocp.ShootingMethod.SINGLE), |
| 112 | + metadata=og.config.OptimizerMeta().with_optimizer_name("ocp_single_tcp"), |
| 113 | + build_configuration=og.config.BuildConfiguration() |
| 114 | + .with_open_version(local_path=OcpTestCase.get_open_local_absolute_path()) |
| 115 | + .with_build_directory(OcpTestCase.TEST_DIR) |
| 116 | + .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) |
| 117 | + .with_tcp_interface_config( |
| 118 | + tcp_interface_config=og.config.TcpServerConfiguration(bind_port=3391) |
| 119 | + ), |
| 120 | + solver_configuration=solver_config, |
| 121 | + ).build() |
| 122 | + cls.ocp2_multiple_optimizer = og.ocp.OCPBuilder( |
| 123 | + make_problem(og.ocp.ShootingMethod.MULTIPLE), |
| 124 | + metadata=og.config.OptimizerMeta().with_optimizer_name("ocp_multiple_tcp"), |
| 125 | + build_configuration=og.config.BuildConfiguration() |
| 126 | + .with_open_version(local_path=OcpTestCase.get_open_local_absolute_path()) |
| 127 | + .with_build_directory(OcpTestCase.TEST_DIR) |
| 128 | + .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) |
| 129 | + .with_tcp_interface_config( |
| 130 | + tcp_interface_config=og.config.TcpServerConfiguration(bind_port=3392) |
| 131 | + ), |
| 132 | + solver_configuration=solver_config, |
| 133 | + ).build() |
| 134 | + |
| 135 | + cls.ocp2_single_optimizer.save() |
| 136 | + cls.ocp2_multiple_optimizer.save() |
| 137 | + cls.ocp2_single_manifest_path = os.path.join( |
| 138 | + cls.ocp2_single_optimizer.target_dir, "optimizer_manifest.json") |
| 139 | + cls.ocp2_multiple_manifest_path = os.path.join( |
| 140 | + cls.ocp2_multiple_optimizer.target_dir, "optimizer_manifest.json") |
| 141 | + |
| 142 | + @classmethod |
| 143 | + def setUpClass(cls): |
| 144 | + cls.setUpOCP1() |
| 145 | + cls.setUpOCP2() |
46 | 146 |
|
47 | 147 | def make_ocp(self, shooting=og.ocp.ShootingMethod.SINGLE): |
48 | 148 | ocp = og.ocp.OptimalControlProblem(nx=2, nu=1, horizon=3, shooting=shooting) |
@@ -324,52 +424,35 @@ def test_generated_optimizer_defaults(self): |
324 | 424 | self.assertAlmostEqual(result.states[-1][1], -0.6) |
325 | 425 |
|
326 | 426 | def test_optimizer_manifest_roundtrip(self): |
327 | | - optimizer_name = "ocp_manifest_bindings" |
328 | | - ocp = og.ocp.OptimalControlProblem(nx=2, nu=1, horizon=3) |
329 | | - ocp.add_parameter("x0", 2) |
330 | | - ocp.add_parameter("xref", 2, default=[0.0, 0.0]) |
331 | | - ocp.with_dynamics(lambda x, u, param: cs.vertcat(x[0] + u[0], x[1] - u[0])) |
332 | | - ocp.with_stage_cost( |
333 | | - lambda x, u, param, _t: cs.dot(x - param["xref"], x - param["xref"]) + 0.1 * cs.dot(u, u) |
334 | | - ) |
335 | | - ocp.with_terminal_cost( |
336 | | - lambda x, param: cs.dot(x - param["xref"], x - param["xref"]) |
337 | | - ) |
338 | | - ocp.with_input_constraints(og.constraints.Rectangle([-1.0], [1.0])) |
339 | | - |
340 | | - optimizer = og.ocp.OCPBuilder( |
341 | | - ocp, |
342 | | - metadata=og.config.OptimizerMeta().with_optimizer_name(optimizer_name), |
343 | | - build_configuration=og.config.BuildConfiguration() |
344 | | - .with_open_version(local_path=OcpTestCase.get_open_local_absolute_path()) |
345 | | - .with_build_directory(OcpTestCase.TEST_DIR) |
346 | | - .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) |
347 | | - .with_build_python_bindings(), |
348 | | - solver_configuration=og.config.SolverConfiguration() |
349 | | - .with_tolerance(1e-5) |
350 | | - .with_delta_tolerance(1e-5) |
351 | | - .with_initial_penalty(10.0) |
352 | | - .with_penalty_weight_update_factor(1.2) |
353 | | - .with_max_inner_iterations(500) |
354 | | - .with_max_outer_iterations(10), |
355 | | - ).build() |
356 | | - |
357 | | - optimizer.save() |
358 | | - manifest_path = os.path.join(optimizer.target_dir, "optimizer_manifest.json") |
359 | | - rollout_path = os.path.join(optimizer.target_dir, "rollout.casadi") |
| 427 | + manifest_path = self.ocp1_manifest_path |
| 428 | + rollout_path = self.ocp1_rollout_path |
360 | 429 |
|
361 | 430 | self.assertTrue(os.path.exists(manifest_path)) |
362 | 431 | self.assertTrue(os.path.exists(rollout_path)) |
363 | 432 |
|
| 433 | + with open(manifest_path, "r") as fh: |
| 434 | + manifest = json.load(fh) |
| 435 | + |
| 436 | + self.assertEqual(1, manifest["manifest_version"]) |
| 437 | + self.assertEqual("ocp_manifest_bindings", manifest["optimizer_name"]) |
| 438 | + self.assertEqual("direct", manifest["backend_kind"]) |
| 439 | + self.assertEqual("single", manifest["shooting"]) |
| 440 | + self.assertEqual(2, manifest["nx"]) |
| 441 | + self.assertEqual(1, manifest["nu"]) |
| 442 | + self.assertEqual(3, manifest["horizon"]) |
| 443 | + self.assertEqual(3, manifest["decision_dimension"]) |
| 444 | + self.assertEqual(6, manifest["parameter_dimension"]) # p = (x0, xref, q, r) |
| 445 | + self.assertEqual("rollout.casadi", manifest["rollout_file"]) |
| 446 | + self.assertIsNotNone(manifest["rollout_sha256"]) |
| 447 | + self.assertIn("created_at", manifest) |
| 448 | + |
364 | 449 | loaded_optimizer = og.ocp.GeneratedOptimizer.load(manifest_path) |
365 | 450 |
|
366 | 451 | result = loaded_optimizer.solve( |
367 | | - x0=[1.0, 0.0], |
368 | | - xref=[0.0, 0.0], |
369 | | - initial_guess=[0.0] * 3, |
| 452 | + x0=[1.0, 0.0] |
370 | 453 | ) |
371 | 454 |
|
372 | | - self.assertEqual(optimizer_name, loaded_optimizer.optimizer_name) |
| 455 | + self.assertEqual("ocp_manifest_bindings", loaded_optimizer.optimizer_name) |
373 | 456 | self.assertEqual("direct", loaded_optimizer.backend_kind) |
374 | 457 | self.assertEqual("Converged", result.exit_status) |
375 | 458 | self.assertEqual(3, len(result.inputs)) |
@@ -440,62 +523,8 @@ def test_multiple_shooting_state_extraction(self): |
440 | 523 | self.assertEqual(result.states, [[0.0, 0.0], [0.1, -0.1], [0.3, -0.3], [0.7, -0.7]]) |
441 | 524 |
|
442 | 525 | def test_single_vs_multiple(self): |
443 | | - def make_problem(shooting): |
444 | | - ocp = og.ocp.OptimalControlProblem(nx=2, nu=1, horizon=5, shooting=shooting) |
445 | | - ocp.add_parameter("x0", 2) |
446 | | - ocp.add_parameter("xref", 2, default=[0.0, 0.0]) |
447 | | - ocp.with_dynamics(lambda x, u, param: |
448 | | - cs.vertcat(x[0] + u[0], x[1] - u[0])) |
449 | | - ocp.with_stage_cost( |
450 | | - lambda x, u, param, _t: |
451 | | - cs.dot(x - param["xref"], x - param["xref"]) + 0.01 * cs.dot(u, u) |
452 | | - ) |
453 | | - ocp.with_terminal_cost( |
454 | | - lambda x, param: |
455 | | - 2.0 * cs.dot(x - param["xref"], x - param["xref"]) |
456 | | - ) |
457 | | - ocp.with_input_constraints(og.constraints.Rectangle([-0.4], [0.4])) |
458 | | - ocp.with_path_constraint( |
459 | | - lambda x, u, param, _t: cs.fmax(0.0, x[0] - 1.5) |
460 | | - ) |
461 | | - if shooting == og.ocp.ShootingMethod.MULTIPLE: |
462 | | - ocp.with_dynamics_constraints("alm") |
463 | | - return ocp |
464 | | - |
465 | | - solver_config = og.config.SolverConfiguration() \ |
466 | | - .with_tolerance(1e-5) \ |
467 | | - .with_delta_tolerance(1e-5) \ |
468 | | - .with_initial_penalty(10.0) \ |
469 | | - .with_penalty_weight_update_factor(1.2) \ |
470 | | - .with_max_inner_iterations(5000) \ |
471 | | - .with_max_outer_iterations(20) |
472 | | - |
473 | | - ocp_single = make_problem(og.ocp.ShootingMethod.SINGLE) |
474 | | - single_optimizer = og.ocp.OCPBuilder( |
475 | | - ocp_single, |
476 | | - metadata=og.config.OptimizerMeta().with_optimizer_name("ocp_single_tcp"), |
477 | | - build_configuration=og.config.BuildConfiguration() |
478 | | - .with_open_version(local_path=OcpTestCase.get_open_local_absolute_path()) |
479 | | - .with_build_directory(OcpTestCase.TEST_DIR) |
480 | | - .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) |
481 | | - .with_tcp_interface_config( |
482 | | - tcp_interface_config=og.config.TcpServerConfiguration(bind_port=3391) |
483 | | - ), |
484 | | - solver_configuration=solver_config, |
485 | | - ).build() |
486 | | - ocp_multiple = make_problem(og.ocp.ShootingMethod.MULTIPLE) |
487 | | - multiple_optimizer = og.ocp.OCPBuilder( |
488 | | - ocp_multiple, |
489 | | - metadata=og.config.OptimizerMeta().with_optimizer_name("ocp_multiple_tcp"), |
490 | | - build_configuration=og.config.BuildConfiguration() |
491 | | - .with_open_version(local_path=OcpTestCase.get_open_local_absolute_path()) |
492 | | - .with_build_directory(OcpTestCase.TEST_DIR) |
493 | | - .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) |
494 | | - .with_tcp_interface_config( |
495 | | - tcp_interface_config=og.config.TcpServerConfiguration(bind_port=3392) |
496 | | - ), |
497 | | - solver_configuration=solver_config, |
498 | | - ).build() |
| 526 | + single_optimizer = og.ocp.GeneratedOptimizer.load(self.ocp2_single_manifest_path) |
| 527 | + multiple_optimizer = og.ocp.GeneratedOptimizer.load(self.ocp2_multiple_manifest_path) |
499 | 528 |
|
500 | 529 | try: |
501 | 530 | x0 = [1.0, -1.0] |
|
0 commit comments