forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcost.cc
309 lines (259 loc) · 9.5 KB
/
cost.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
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
#include "drake/solvers/cost.h"
#include <memory>
#include "drake/math/autodiff_gradient.h"
using Eigen::MatrixXd;
using Eigen::VectorXd;
using std::make_shared;
using std::shared_ptr;
namespace drake {
namespace solvers {
namespace {
std::ostream& DisplayCost(const Cost& cost, std::ostream& os,
const std::string& name,
const VectorX<symbolic::Variable>& vars) {
os << name;
// Append the expression.
VectorX<symbolic::Expression> e;
cost.Eval(vars, &e);
DRAKE_DEMAND(e.size() == 1);
os << " " << e[0];
// Append the description (when provided).
const std::string& description = cost.get_description();
if (!description.empty()) {
os << " described as '" << description << "'";
}
return os;
}
} // namespace
template <typename DerivedX, typename U>
void LinearCost::DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<U>* y) const {
y->resize(1);
(*y)(0) = a_.dot(x) + b_;
}
void LinearCost::DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const {
DoEvalGeneric(x, y);
}
void LinearCost::DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const {
DoEvalGeneric(x, y);
}
void LinearCost::DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const {
DoEvalGeneric(x, y);
}
std::ostream& LinearCost::DoDisplay(
std::ostream& os, const VectorX<symbolic::Variable>& vars) const {
return DisplayCost(*this, os, "LinearCost", vars);
}
template <typename DerivedX, typename U>
void QuadraticCost::DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<U>* y) const {
y->resize(1);
*y = .5 * x.transpose() * Q_ * x + b_.transpose() * x;
(*y)(0) += c_;
}
void QuadraticCost::DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const {
DoEvalGeneric(x, y);
}
void QuadraticCost::DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const {
// Specialized evaluation of cost and gradient
const MatrixXd dx = math::ExtractGradient(x);
const Eigen::VectorXd x_val = drake::math::ExtractValue(x);
const Eigen::RowVectorXd xT_times_Q = x_val.transpose() * Q_;
const Vector1d result(.5 * xT_times_Q.dot(x_val) + b_.dot(x_val) + c_);
const Eigen::RowVectorXd dy = xT_times_Q + b_.transpose();
// If dx is the identity matrix (very common here), then skip the chain rule
// multiplication dy * dx
if (dx.rows() == x.size() && dx.cols() == x.size() &&
dx == MatrixXd::Identity(x.size(), x.size())) {
*y = math::InitializeAutoDiff(result, dy);
} else {
*y = math::InitializeAutoDiff(result, dy * dx);
}
}
void QuadraticCost::DoEval(
const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const {
DoEvalGeneric(x, y);
}
std::ostream& QuadraticCost::DoDisplay(
std::ostream& os, const VectorX<symbolic::Variable>& vars) const {
return DisplayCost(*this, os, "QuadraticCost", vars);
}
bool QuadraticCost::CheckHessianPsd() {
Eigen::LDLT<Eigen::MatrixXd> ldlt_solver;
ldlt_solver.compute(Q_);
return ldlt_solver.isPositive();
}
shared_ptr<QuadraticCost> MakeQuadraticErrorCost(
const Eigen::Ref<const MatrixXd>& Q,
const Eigen::Ref<const VectorXd>& x_desired) {
const double c = x_desired.dot(Q * x_desired);
return make_shared<QuadraticCost>(2 * Q, -2 * Q * x_desired, c);
}
shared_ptr<QuadraticCost> Make2NormSquaredCost(
const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b) {
const double c = b.dot(b);
return make_shared<QuadraticCost>(2 * A.transpose() * A,
-2 * A.transpose() * b, c,
true /* Hessian is psd */);
}
L1NormCost::L1NormCost(const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b)
: Cost(A.cols()), A_(A), b_(b) {
DRAKE_DEMAND(A_.rows() == b_.rows());
}
void L1NormCost::UpdateCoefficients(
const Eigen::Ref<const Eigen::MatrixXd>& new_A,
const Eigen::Ref<const Eigen::VectorXd>& new_b) {
if (new_A.cols() != A_.cols()) {
throw std::runtime_error("Can't change the number of decision variables");
}
if (new_A.rows() != new_b.rows()) {
throw std::runtime_error("A and b must have the same number of rows.");
}
A_ = new_A;
b_ = new_b;
}
void L1NormCost::DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).lpNorm<1>();
}
void L1NormCost::DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).lpNorm<1>();
}
void L1NormCost::DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).cwiseAbs().sum();
}
std::ostream& L1NormCost::DoDisplay(
std::ostream& os, const VectorX<symbolic::Variable>& vars) const {
return DisplayCost(*this, os, "L1NormCost", vars);
}
L2NormCost::L2NormCost(const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b)
: Cost(A.cols()), A_(A), b_(b) {
DRAKE_DEMAND(A_.rows() == b_.rows());
}
void L2NormCost::UpdateCoefficients(
const Eigen::Ref<const Eigen::MatrixXd>& new_A,
const Eigen::Ref<const Eigen::VectorXd>& new_b) {
if (new_A.cols() != A_.cols()) {
throw std::runtime_error("Can't change the number of decision variables");
}
if (new_A.rows() != new_b.rows()) {
throw std::runtime_error("A and b must have the same number of rows.");
}
A_ = new_A;
b_ = new_b;
}
void L2NormCost::DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).norm();
}
void L2NormCost::DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).norm();
}
void L2NormCost::DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const {
y->resize(1);
(*y)(0) = sqrt((A_ * x + b_).squaredNorm());
}
std::ostream& L2NormCost::DoDisplay(
std::ostream& os, const VectorX<symbolic::Variable>& vars) const {
return DisplayCost(*this, os, "L2NormCost", vars);
}
LInfNormCost::LInfNormCost(const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b)
: Cost(A.cols()), A_(A), b_(b) {
DRAKE_DEMAND(A_.rows() == b_.rows());
}
void LInfNormCost::UpdateCoefficients(
const Eigen::Ref<const Eigen::MatrixXd>& new_A,
const Eigen::Ref<const Eigen::VectorXd>& new_b) {
if (new_A.cols() != A_.cols()) {
throw std::runtime_error("Can't change the number of decision variables");
}
if (new_A.rows() != new_b.rows()) {
throw std::runtime_error("A and b must have the same number of rows.");
}
A_ = new_A;
b_ = new_b;
}
void LInfNormCost::DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).lpNorm<Eigen::Infinity>();
}
void LInfNormCost::DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).lpNorm<Eigen::Infinity>();
}
void LInfNormCost::DoEval(
const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const {
y->resize(1);
(*y)(0) = (A_ * x + b_).cwiseAbs().maxCoeff();
}
std::ostream& LInfNormCost::DoDisplay(
std::ostream& os, const VectorX<symbolic::Variable>& vars) const {
return DisplayCost(*this, os, "LInfNormCost", vars);
}
PerspectiveQuadraticCost::PerspectiveQuadraticCost(
const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b)
: Cost(A.cols()), A_(A), b_(b) {
DRAKE_DEMAND(A_.rows() >= 2);
DRAKE_DEMAND(A_.rows() == b_.rows());
}
void PerspectiveQuadraticCost::UpdateCoefficients(
const Eigen::Ref<const Eigen::MatrixXd>& new_A,
const Eigen::Ref<const Eigen::VectorXd>& new_b) {
if (new_A.cols() != A_.cols()) {
throw std::runtime_error("Can't change the number of decision variables");
}
if (new_A.rows() != new_b.rows()) {
throw std::runtime_error("A and b must have the same number of rows.");
}
A_ = new_A;
b_ = new_b;
}
template <typename DerivedX, typename U>
void PerspectiveQuadraticCost::DoEvalGeneric(
const Eigen::MatrixBase<DerivedX>& x, VectorX<U>* y) const {
y->resize(1);
VectorX<U> z = A_ * x.template cast<U>() + b_;
(*y)(0) = z.tail(z.size() - 1).squaredNorm() / z(0);
}
void PerspectiveQuadraticCost::DoEval(
const Eigen::Ref<const Eigen::VectorXd>& x, Eigen::VectorXd* y) const {
DoEvalGeneric(x, y);
}
void PerspectiveQuadraticCost::DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const {
DoEvalGeneric(x, y);
}
void PerspectiveQuadraticCost::DoEval(
const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const {
DoEvalGeneric(x, y);
}
std::ostream& PerspectiveQuadraticCost::DoDisplay(
std::ostream& os, const VectorX<symbolic::Variable>& vars) const {
return DisplayCost(*this, os, "PerspectiveQuadraticCost", vars);
}
} // namespace solvers
} // namespace drake