Skip to content

Commit 75fc21f

Browse files
authored
Convex hulls of multiple convex sets (#21594)
* Convex hulls of multiple convex sets * fix typo * remove unnecessary headers * remove std::move * address Alex's comments * address comments * augment test and address comments * empty tests * last form * remove optional and address comments * address Grant's comments * grammar fix
1 parent cae8253 commit 75fc21f

File tree

4 files changed

+617
-0
lines changed

4 files changed

+617
-0
lines changed

geometry/optimization/BUILD.bazel

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@ drake_cc_library(
5151
"affine_ball.cc",
5252
"affine_subspace.cc",
5353
"cartesian_product.cc",
54+
"convex_hull.cc",
5455
"convex_set.cc",
5556
"hpolyhedron.cc",
5657
"hyperellipsoid.cc",
@@ -65,6 +66,7 @@ drake_cc_library(
6566
"affine_ball.h",
6667
"affine_subspace.h",
6768
"cartesian_product.h",
69+
"convex_hull.h",
6870
"convex_set.h",
6971
"hpolyhedron.h",
7072
"hyperellipsoid.h",
@@ -275,6 +277,16 @@ drake_cc_googletest(
275277
],
276278
)
277279

280+
drake_cc_googletest(
281+
name = "convex_hull_test",
282+
deps = [
283+
":convex_set",
284+
":test_utilities",
285+
"//common/test_utilities:eigen_matrix_compare",
286+
"//common/test_utilities:expect_throws_message",
287+
],
288+
)
289+
278290
drake_cc_googletest(
279291
name = "convex_set_test",
280292
deps = [

geometry/optimization/convex_hull.cc

Lines changed: 272 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,272 @@
1+
#include "drake/geometry/optimization/convex_hull.h"
2+
3+
#include <limits>
4+
#include <memory>
5+
6+
#include <drake/common/symbolic/expression/variables.h>
7+
8+
#include "drake/solvers/solve.h"
9+
10+
namespace drake {
11+
namespace geometry {
12+
namespace optimization {
13+
14+
using Eigen::Map;
15+
using Eigen::MatrixXd;
16+
using Eigen::VectorXd;
17+
using solvers::Binding;
18+
using solvers::Constraint;
19+
using solvers::LinearConstraint;
20+
using solvers::MathematicalProgram;
21+
using solvers::ProgramAttribute;
22+
using solvers::ProgramAttributes;
23+
using solvers::VectorXDecisionVariable;
24+
using symbolic::Expression;
25+
using symbolic::Variable;
26+
27+
namespace {
28+
29+
int GetAmbientDimension(const ConvexSets& sets) {
30+
if (sets.empty()) {
31+
return 0;
32+
}
33+
const int ambient_dimension = sets[0]->ambient_dimension();
34+
for (const copyable_unique_ptr<ConvexSet>& set : sets) {
35+
DRAKE_THROW_UNLESS(set != nullptr);
36+
DRAKE_THROW_UNLESS(set->ambient_dimension() == ambient_dimension);
37+
}
38+
return ambient_dimension;
39+
}
40+
41+
// Add the new variables to the existing_variables from the bindings.
42+
void AddNewVariables(
43+
const std::vector<solvers::Binding<solvers::Constraint>>& bindings,
44+
symbolic::Variables* existing_variables) {
45+
for (const auto& binding : bindings) {
46+
const auto& vars = binding.variables();
47+
existing_variables->insert(symbolic::Variables(vars));
48+
}
49+
}
50+
51+
// Given a vector of convex sets, return a vector of non-empty convex sets if
52+
// remove_empty_sets is true, otherwise return the original vector.
53+
ConvexSets MakeParticipartingSets(const ConvexSets& sets,
54+
const bool remove_empty_sets) {
55+
if (!remove_empty_sets) {
56+
return sets;
57+
}
58+
ConvexSets non_empty_sets;
59+
for (const auto& set : sets) {
60+
if (!set->IsEmpty()) {
61+
non_empty_sets.push_back(set);
62+
}
63+
}
64+
return non_empty_sets;
65+
}
66+
} // namespace
67+
68+
ConvexHull::ConvexHull(const ConvexSets& sets, const bool remove_empty_sets)
69+
: ConvexSet(GetAmbientDimension(sets), false),
70+
sets_(sets),
71+
participating_sets_{MakeParticipartingSets(sets_, remove_empty_sets)},
72+
empty_sets_removed_(remove_empty_sets) {}
73+
74+
ConvexHull::~ConvexHull() = default;
75+
76+
const ConvexSet& ConvexHull::element(int index) const {
77+
DRAKE_THROW_UNLESS(0 <= index && index < std::ssize(sets_));
78+
return *sets_[index];
79+
}
80+
81+
std::unique_ptr<ConvexSet> ConvexHull::DoClone() const {
82+
return std::make_unique<ConvexHull>(*this);
83+
}
84+
85+
std::optional<bool> ConvexHull::DoIsBoundedShortcut() const {
86+
return std::nullopt;
87+
}
88+
89+
bool ConvexHull::DoIsEmpty() const {
90+
if (empty_sets_removed_) {
91+
return participating_sets_.empty();
92+
}
93+
// If empty_sets_removed_ is false, then we reconstruct the
94+
// participating_sets_ and check if it is empty.
95+
return ConvexHull(sets_, true).IsEmpty();
96+
}
97+
98+
std::optional<VectorXd> ConvexHull::DoMaybeGetPoint() const {
99+
return std::nullopt;
100+
}
101+
102+
bool ConvexHull::DoPointInSet(const Eigen::Ref<const Eigen::VectorXd>& x,
103+
double tol) const {
104+
// Check the feasibility of |x - ∑ᵢ xᵢ| <= tol * 1, xᵢ ∈ 𝛼ᵢXᵢ, 𝛼ᵢ ≥ 0, ∑ᵢ 𝛼ᵢ =
105+
// 1, where 1 is a vector of ones and |.| is interpreted element-wise.
106+
MathematicalProgram prog;
107+
const int n = std::ssize(participating_sets_);
108+
const int d = ambient_dimension();
109+
// x_sets is d * n, each column is a variable for a convex set
110+
auto x_sets = prog.NewContinuousVariables(d, n, "x_sets");
111+
auto alpha = prog.NewContinuousVariables(n, "alpha");
112+
// constraint: x - tol * 1 ≤ ∑ᵢ xᵢ ≤ x + tol * 1
113+
Eigen::VectorXd ones = Eigen::VectorXd::Ones(n);
114+
for (int i = 0; i < d; ++i) {
115+
prog.AddLinearConstraint(Eigen::VectorXd::Ones(n), x(i) - tol, x(i) + tol,
116+
x_sets.row(i));
117+
}
118+
// constraint: ∑ᵢ αᵢ = 1
119+
prog.AddLinearEqualityConstraint(Eigen::MatrixXd::Ones(1, n),
120+
VectorXd::Ones(1), alpha);
121+
// constraint: 1 ≥ αᵢ ≥ 0
122+
prog.AddBoundingBoxConstraint(0, 1, alpha);
123+
// Add the constraints for each convex set.
124+
for (int i = 0; i < n; ++i) {
125+
participating_sets_[i]->AddPointInNonnegativeScalingConstraints(
126+
&prog, x_sets.col(i), alpha(i));
127+
}
128+
// Check feasibility.
129+
const auto result = solvers::Solve(prog);
130+
return result.is_success();
131+
}
132+
133+
std::pair<VectorX<symbolic::Variable>,
134+
std::vector<solvers::Binding<solvers::Constraint>>>
135+
ConvexHull::DoAddPointInSetConstraints(
136+
solvers::MathematicalProgram* prog,
137+
const Eigen::Ref<const solvers::VectorXDecisionVariable>& vars) const {
138+
// Add the constraint that vars = ∑ᵢ xᵢ, xᵢ ∈ 𝛼ᵢXᵢ, 𝛼ᵢ ≥ 0, ∑ᵢ 𝛼ᵢ = 1.
139+
const int n = std::ssize(participating_sets_);
140+
const int d = ambient_dimension();
141+
// The variable is d * n, each column is a variable for a convex set
142+
auto x_sets = prog->NewContinuousVariables(d, n, "x_sets");
143+
auto alpha = prog->NewContinuousVariables(n, "alpha");
144+
std::vector<solvers::Binding<solvers::Constraint>> new_bindings;
145+
new_bindings.push_back(prog->AddBoundingBoxConstraint(0, 1, alpha));
146+
// constraint: vars - ∑ᵢ xᵢ == 0 -> (1 ... 1 -1)(x_sets[i, :], vars) = 0
147+
Eigen::VectorXd a(n + 1);
148+
a.head(n) = Eigen::VectorXd::Ones(n);
149+
a(n) = -1;
150+
for (int i = 0; i < d; ++i) {
151+
Eigen::Ref<const solvers::VectorXDecisionVariable> vars_i =
152+
vars.segment(i, 1);
153+
solvers::VectorXDecisionVariable x_i_vars(n + 1);
154+
x_i_vars.head(n) = x_sets.row(i);
155+
x_i_vars(n) = vars(i);
156+
new_bindings.push_back(prog->AddLinearEqualityConstraint(a, 0, x_i_vars));
157+
}
158+
// constraint: ∑ᵢ αᵢ = 1
159+
new_bindings.push_back(prog->AddLinearEqualityConstraint(
160+
Eigen::MatrixXd::Ones(1, n), VectorXd::Ones(1), alpha));
161+
auto new_vars = drake::symbolic::Variables();
162+
// add the constraints for each convex set
163+
for (int i = 0; i < n; ++i) {
164+
auto cons = participating_sets_[i]->AddPointInNonnegativeScalingConstraints(
165+
prog, x_sets.col(i), alpha(i));
166+
new_bindings.insert(new_bindings.end(), cons.begin(), cons.end());
167+
AddNewVariables(cons, &new_vars);
168+
}
169+
// Convert to std::vector<symbolic::Variable> because sets do not have
170+
// contiguous memory.
171+
std::vector<symbolic::Variable> new_vars_vec(new_vars.size());
172+
std::move(new_vars.begin(), new_vars.end(), new_vars_vec.begin());
173+
return std::make_pair(Eigen::Map<VectorX<symbolic::Variable>>(
174+
new_vars_vec.data(), new_vars_vec.size()),
175+
std::move(new_bindings));
176+
}
177+
178+
std::vector<solvers::Binding<solvers::Constraint>>
179+
ConvexHull::DoAddPointInNonnegativeScalingConstraints(
180+
solvers::MathematicalProgram* prog,
181+
const Eigen::Ref<const solvers::VectorXDecisionVariable>& x,
182+
const symbolic::Variable& t) const {
183+
// Add the constraint that t >= 0, x = ∑ᵢ xᵢ, xᵢ ∈ 𝛼ᵢXᵢ, 𝛼ᵢ ≥ 0, ∑ᵢ 𝛼ᵢ = t.
184+
const int n = std::ssize(participating_sets_);
185+
const int d = ambient_dimension();
186+
// The new variable is d * n, each row is a variable for a convex set
187+
auto x_sets = prog->NewContinuousVariables(d, n, "x_sets");
188+
auto alpha = prog->NewContinuousVariables(n, "alpha");
189+
const double inf = std::numeric_limits<double>::infinity();
190+
std::vector<solvers::Binding<solvers::Constraint>> new_bindings;
191+
// Constraint I: -x + ∑ᵢ xᵢ == 0
192+
Eigen::VectorXd a(n + 1);
193+
a.head(n) = Eigen::VectorXd::Ones(n);
194+
a(n) = -1;
195+
for (int i = 0; i < d; ++i) {
196+
solvers::VectorXDecisionVariable x_sets_i_x(n + 1);
197+
x_sets_i_x.head(n) = x_sets.row(i);
198+
x_sets_i_x(n) = x(i);
199+
new_bindings.push_back(prog->AddLinearEqualityConstraint(a, 0, x_sets_i_x));
200+
}
201+
// Constraint II: ∑ᵢ αᵢ = t
202+
solvers::VectorXDecisionVariable alpha_t_vec(n + 1);
203+
alpha_t_vec.head(n) = alpha;
204+
alpha_t_vec(n) = t;
205+
new_bindings.push_back(prog->AddLinearEqualityConstraint(a, 0, alpha_t_vec));
206+
// alpha should be positive.
207+
new_bindings.push_back(prog->AddBoundingBoxConstraint(0, inf, alpha));
208+
// Finally add the constraints for each convex set.
209+
for (int i = 0; i < n; ++i) {
210+
auto cons = participating_sets_[i]->AddPointInNonnegativeScalingConstraints(
211+
prog, x_sets.col(i), alpha(i));
212+
new_bindings.insert(new_bindings.end(), cons.begin(), cons.end());
213+
}
214+
return new_bindings;
215+
}
216+
217+
std::vector<solvers::Binding<solvers::Constraint>>
218+
ConvexHull::DoAddPointInNonnegativeScalingConstraints(
219+
solvers::MathematicalProgram* prog,
220+
const Eigen::Ref<const Eigen::MatrixXd>& A_x,
221+
const Eigen::Ref<const Eigen::VectorXd>& b_x,
222+
const Eigen::Ref<const Eigen::VectorXd>& c, double d,
223+
const Eigen::Ref<const solvers::VectorXDecisionVariable>& x,
224+
const Eigen::Ref<const solvers::VectorXDecisionVariable>& t) const {
225+
// Add the constraint that A_x * x + b_x = ∑ᵢ xᵢ, xᵢ ∈ 𝛼ᵢXᵢ, 𝛼ᵢ ≥ 0,
226+
// ∑ᵢ 𝛼ᵢ = c't + d.
227+
const int dim = ambient_dimension();
228+
const int n = std::ssize(participating_sets_);
229+
// The new variable is dim * n, each column belongs to a convex set.
230+
auto x_sets = prog->NewContinuousVariables(dim, n, "x_sets");
231+
auto alpha = prog->NewContinuousVariables(n, "alpha");
232+
std::vector<solvers::Binding<solvers::Constraint>> new_bindings;
233+
// constraint: A_x * x - ∑ᵢ sᵢ == -b_x
234+
for (int i = 0; i < dim; ++i) {
235+
// A_x.row(i) * x - (1, ..., 1) xᵢ == -b_x[i]
236+
solvers::VectorXDecisionVariable x_sets_i_(dim + n);
237+
x_sets_i_.head(dim) = x;
238+
x_sets_i_.tail(n) = x_sets.row(i);
239+
Eigen::VectorXd a_sum(A_x.cols() + n);
240+
a_sum.head(A_x.cols()) = A_x.row(i);
241+
a_sum.tail(n) = -Eigen::VectorXd::Ones(n);
242+
new_bindings.push_back(
243+
prog->AddLinearEqualityConstraint(a_sum, -b_x[i], x_sets_i_));
244+
}
245+
// constraint: ∑ᵢ αᵢ = c't + d
246+
const int p = c.size();
247+
Eigen::VectorXd a_con(n + p);
248+
a_con.head(n) = Eigen::VectorXd::Ones(n);
249+
a_con.tail(p) = -c;
250+
solvers::VectorXDecisionVariable alpha_t_vec(n + p);
251+
alpha_t_vec.head(n) = alpha;
252+
alpha_t_vec.tail(p) = t;
253+
new_bindings.push_back(
254+
prog->AddLinearEqualityConstraint(a_con, d, alpha_t_vec));
255+
// Add the inclusion constraints for each convex set.
256+
for (int i = 0; i < n; ++i) {
257+
auto cons = participating_sets_[i]->AddPointInNonnegativeScalingConstraints(
258+
prog, x_sets.col(i), alpha(i));
259+
new_bindings.insert(new_bindings.end(), cons.begin(), cons.end());
260+
}
261+
return new_bindings;
262+
}
263+
264+
std::pair<std::unique_ptr<Shape>, math::RigidTransformd>
265+
ConvexHull::DoToShapeWithPose() const {
266+
throw std::runtime_error(
267+
"ToShapeWithPose is not implemented yet for ConvexHull.");
268+
}
269+
270+
} // namespace optimization
271+
} // namespace geometry
272+
} // namespace drake

0 commit comments

Comments
 (0)