Skip to content

Commit

Permalink
Implement add_compatibility_w_u_polyhedron function.
Browse files Browse the repository at this point in the history
When the admissible input set is described as a V-rep polyhedron, we can use an alternative formulation to impose the compatibility.
  • Loading branch information
hongkai-dai committed Sep 16, 2024
1 parent 656efc8 commit 3e3b731
Show file tree
Hide file tree
Showing 11 changed files with 715 additions and 241 deletions.
574 changes: 441 additions & 133 deletions compatible_clf_cbf/clf_cbf.py

Large diffs are not rendered by default.

11 changes: 3 additions & 8 deletions examples/linear_toy/linear_toy_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,17 +24,12 @@ def search_compatible_lagrangians(

# Search for the
lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[
clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0) for _ in range(dut.nu)
],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0),
lambda_y=[clf_cbf.XYDegree(x=2, y=0) for _ in range(dut.nu)],
xi_y=clf_cbf.XYDegree(x=2, y=0),
y=(
None
if dut.use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0)
for _ in range(y_size)
]
else [clf_cbf.XYDegree(x=2, y=0) for _ in range(y_size)]
),
rho_minus_V=None,
h_plus_eps=None,
Expand Down
15 changes: 5 additions & 10 deletions examples/linear_toy/linear_toy_w_input_limits_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,20 +25,15 @@ def search_compatible_lagrangians(
y_size = dut.y.size

lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[
clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0) for _ in range(dut.nu)
],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0),
lambda_y=[clf_cbf.XYDegree(x=2, y=0) for _ in range(dut.nu)],
xi_y=clf_cbf.XYDegree(x=2, y=0),
y=(
None
if dut.use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0)
for _ in range(y_size)
]
else [clf_cbf.XYDegree(x=2, y=0) for _ in range(y_size)]
),
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=2, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=2, y=2)],
state_eq_constraints=None,
)
prog, lagrangians = dut.construct_search_compatible_lagrangians(
Expand Down
13 changes: 5 additions & 8 deletions examples/nonlinear_toy/demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,18 +41,15 @@ def main(use_y_squared: bool, with_u_bound: bool):
kappa_h = np.array([kappa_V])

lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=3, y=0)],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0),
lambda_y=[clf_cbf.XYDegree(x=3, y=0)],
xi_y=clf_cbf.XYDegree(x=2, y=0),
y=(
None
if use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=0)
for _ in range(compatible.y.size)
]
else [clf_cbf.XYDegree(x=4, y=0) for _ in range(compatible.y.size)]
),
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=2, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=2, y=2)],
state_eq_constraints=None,
)
barrier_eps = np.array([0.0001])
Expand Down
10 changes: 5 additions & 5 deletions examples/nonlinear_toy/demo_trigpoly.py
Original file line number Diff line number Diff line change
Expand Up @@ -146,12 +146,12 @@ def search(unit_test_flag: bool = False):
V_init, h_init = get_clf_cbf_init(x)

compatible_lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0)],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0),
lambda_y=[clf_cbf.XYDegree(x=2, y=0)],
xi_y=clf_cbf.XYDegree(x=2, y=0),
y=None,
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
state_eq_constraints=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=2, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=2, y=2)],
state_eq_constraints=[clf_cbf.XYDegree(x=2, y=2)],
)
safety_sets_lagrangian_degrees = clf_cbf.SafetySetLagrangianDegrees(
exclude=[
Expand Down
8 changes: 4 additions & 4 deletions examples/nonlinear_toy/synthesize_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,11 @@ def main(with_u_bound: bool):
barrier_eps = np.array([0.0001])

compatible_lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=3, y=0)],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0),
lambda_y=[clf_cbf.XYDegree(x=3, y=0)],
xi_y=clf_cbf.XYDegree(x=2, y=0),
y=None,
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=2, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=2, y=2)],
state_eq_constraints=None,
)
safety_sets_lagrangian_degrees = clf_cbf.SafetySetLagrangianDegrees(
Expand Down
18 changes: 5 additions & 13 deletions examples/power_converter/demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,23 +100,15 @@ def search(use_y_squared: bool):
kappa_h = np.array([kappa_V])

compatible_lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[
clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0 if use_y_squared else 1)
for _ in range(2)
],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(
x=2, y=0 if use_y_squared else 1
),
lambda_y=[clf_cbf.XYDegree(x=2, y=0 if use_y_squared else 1) for _ in range(2)],
xi_y=clf_cbf.XYDegree(x=2, y=0 if use_y_squared else 1),
y=(
None
if use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=0)
for _ in range(compatible.y.size)
]
else [clf_cbf.XYDegree(x=4, y=0) for _ in range(compatible.y.size)]
),
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=4, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=4, y=2)],
state_eq_constraints=None,
)

Expand Down
20 changes: 6 additions & 14 deletions examples/quadrotor/demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,24 +100,16 @@ def search(use_y_squared: bool, with_u_bound: bool):
kappa_h_sequences = [np.array([0.2]) for _ in range(len(kappa_V_sequences))]

compatible_lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[
clf_cbf.CompatibleLagrangianDegrees.Degree(x=1, y=0 if use_y_squared else 1)
for _ in range(4)
],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(
x=1, y=0 if use_y_squared else 1
),
lambda_y=[clf_cbf.XYDegree(x=1, y=0 if use_y_squared else 1) for _ in range(4)],
xi_y=clf_cbf.XYDegree(x=1, y=0 if use_y_squared else 1),
y=(
None
if use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=0)
for _ in range(compatible.y.size)
]
else [clf_cbf.XYDegree(x=4, y=0) for _ in range(compatible.y.size)]
),
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
state_eq_constraints=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=2, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=2, y=2)],
state_eq_constraints=[clf_cbf.XYDegree(x=2, y=2)],
)
safety_sets_lagrangian_degrees = [
clf_cbf.SafetySetLagrangianDegrees(
Expand Down
20 changes: 6 additions & 14 deletions examples/quadrotor2d/demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,24 +56,16 @@ def main(use_y_squared: bool, with_u_bound: bool):
solver_options.SetOption(solvers.CommonSolverOption.kPrintToConsole, True)

compatible_lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[
clf_cbf.CompatibleLagrangianDegrees.Degree(x=1, y=0 if use_y_squared else 1)
for _ in range(2)
],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(
x=2, y=0 if use_y_squared else 1
),
lambda_y=[clf_cbf.XYDegree(x=1, y=0 if use_y_squared else 1) for _ in range(2)],
xi_y=clf_cbf.XYDegree(x=2, y=0 if use_y_squared else 1),
y=(
None
if use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=0)
for _ in range(compatible.y.size)
]
else [clf_cbf.XYDegree(x=4, y=0) for _ in range(compatible.y.size)]
),
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
state_eq_constraints=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=2, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=2, y=2)],
state_eq_constraints=[clf_cbf.XYDegree(x=2, y=2)],
)
safety_sets_lagrangian_degrees = clf_cbf.SafetySetLagrangianDegrees(
exclude=[
Expand Down
15 changes: 5 additions & 10 deletions examples/quadrotor2d/demo_taylor.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,20 +71,15 @@ def search_clf_cbf(
state_eq_constraints=None,
)
lagrangian_degrees = clf_cbf.CompatibleLagrangianDegrees(
lambda_y=[
clf_cbf.CompatibleLagrangianDegrees.Degree(x=2, y=0) for _ in range(2)
],
xi_y=clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=0),
lambda_y=[clf_cbf.XYDegree(x=2, y=0) for _ in range(2)],
xi_y=clf_cbf.XYDegree(x=4, y=0),
y=(
None
if use_y_squared
else [
clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=0)
for _ in range(compatible.y.size)
]
else [clf_cbf.XYDegree(x=4, y=0) for _ in range(compatible.y.size)]
),
rho_minus_V=clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=2),
h_plus_eps=[clf_cbf.CompatibleLagrangianDegrees.Degree(x=4, y=2)],
rho_minus_V=clf_cbf.XYDegree(x=4, y=2),
h_plus_eps=[clf_cbf.XYDegree(x=4, y=2)],
state_eq_constraints=None,
)
barrier_eps = np.array([0.0])
Expand Down
Loading

0 comments on commit 3e3b731

Please sign in to comment.