-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
intersection.cc
167 lines (145 loc) · 4.97 KB
/
intersection.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
#include "drake/geometry/optimization/intersection.h"
#include <memory>
#include <fmt/format.h>
namespace drake {
namespace geometry {
namespace optimization {
using Eigen::MatrixXd;
using Eigen::VectorXd;
using solvers::Binding;
using solvers::Constraint;
using solvers::MathematicalProgram;
using solvers::VectorXDecisionVariable;
using symbolic::Variable;
namespace {
int GetAmbientDimension(const ConvexSets& sets) {
if (sets.empty()) {
return 0;
}
const int ambient_dimension = sets[0]->ambient_dimension();
for (const copyable_unique_ptr<ConvexSet>& set : sets) {
DRAKE_THROW_UNLESS(set != nullptr);
DRAKE_THROW_UNLESS(set->ambient_dimension() == ambient_dimension);
}
return ambient_dimension;
}
} // namespace
Intersection::Intersection() : Intersection(ConvexSets{}) {}
Intersection::Intersection(const ConvexSets& sets)
: ConvexSet(GetAmbientDimension(sets), false), sets_(sets) {}
Intersection::Intersection(const ConvexSet& setA, const ConvexSet& setB)
: ConvexSet(setA.ambient_dimension(), false) {
DRAKE_THROW_UNLESS(setB.ambient_dimension() == setA.ambient_dimension());
sets_.emplace_back(setA.Clone());
sets_.emplace_back(setB.Clone());
}
Intersection::~Intersection() = default;
const ConvexSet& Intersection::element(int index) const {
DRAKE_THROW_UNLESS(0 <= index && index < ssize(sets_));
return *sets_[index];
}
std::unique_ptr<ConvexSet> Intersection::DoClone() const {
return std::make_unique<Intersection>(*this);
}
std::optional<bool> Intersection::DoIsBoundedShortcut() const {
for (const auto& s : sets_) {
if (s->IsBounded()) {
return true;
}
}
return std::nullopt;
}
bool Intersection::DoIsEmpty() const {
if (sets_.size() == 0) {
return false;
}
// The empty set is annihilatory in intersection.
for (const auto& s : sets_) {
if (s->IsEmpty()) {
return true;
}
}
// Now actually see if the intersection is nonempty.
return ConvexSet::DoIsEmpty();
}
std::optional<VectorXd> Intersection::DoMaybeGetPoint() const {
std::optional<VectorXd> result;
for (const auto& s : sets_) {
if (std::optional<VectorXd> point = s->MaybeGetPoint()) {
if (result.has_value() && !(*point == *result)) {
return std::nullopt;
}
result = std::move(point);
} else {
return std::nullopt;
}
}
return result;
}
bool Intersection::DoPointInSet(const Eigen::Ref<const VectorXd>& x,
double tol) const {
for (const auto& s : sets_) {
if (!s->PointInSet(x, tol)) {
return false;
}
}
return true;
}
std::pair<VectorX<Variable>, std::vector<Binding<Constraint>>>
Intersection::DoAddPointInSetConstraints(
MathematicalProgram* prog,
const Eigen::Ref<const VectorXDecisionVariable>& x) const {
std::vector<Variable> new_vars;
std::vector<Binding<Constraint>> new_constraints;
for (const auto& s : sets_) {
const auto [new_vars_in_s, new_constraints_in_s] =
s->AddPointInSetConstraints(prog, x);
for (int i = 0; i < new_vars_in_s.rows(); ++i) {
new_vars.push_back(new_vars_in_s(i));
}
new_constraints.insert(new_constraints.end(), new_constraints_in_s.begin(),
new_constraints_in_s.end());
}
VectorX<Variable> new_vars_vec =
Eigen::Map<VectorX<Variable>>(new_vars.data(), new_vars.size());
return {std::move(new_vars_vec), std::move(new_constraints)};
}
std::vector<Binding<Constraint>>
Intersection::DoAddPointInNonnegativeScalingConstraints(
MathematicalProgram* prog,
const Eigen::Ref<const VectorXDecisionVariable>& x,
const Variable& t) const {
std::vector<Binding<Constraint>> constraints;
for (const auto& s : sets_) {
auto new_constraints =
s->AddPointInNonnegativeScalingConstraints(prog, x, t);
constraints.insert(constraints.end(),
std::make_move_iterator(new_constraints.begin()),
std::make_move_iterator(new_constraints.end()));
}
return constraints;
}
std::vector<Binding<Constraint>>
Intersection::DoAddPointInNonnegativeScalingConstraints(
MathematicalProgram* prog, const Eigen::Ref<const MatrixXd>& A,
const Eigen::Ref<const VectorXd>& b, const Eigen::Ref<const VectorXd>& c,
double d, const Eigen::Ref<const VectorXDecisionVariable>& x,
const Eigen::Ref<const VectorXDecisionVariable>& t) const {
std::vector<Binding<Constraint>> constraints;
for (const auto& s : sets_) {
auto new_constraints =
s->AddPointInNonnegativeScalingConstraints(prog, A, b, c, d, x, t);
constraints.insert(constraints.end(),
std::make_move_iterator(new_constraints.begin()),
std::make_move_iterator(new_constraints.end()));
}
return constraints;
}
std::pair<std::unique_ptr<Shape>, math::RigidTransformd>
Intersection::DoToShapeWithPose() const {
throw std::runtime_error(
"ToShapeWithPose is not implemented yet for Intersection.");
}
} // namespace optimization
} // namespace geometry
} // namespace drake