forked from sammy-tri/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
constraint.h
909 lines (776 loc) · 31.3 KB
/
constraint.h
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
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
#pragma once
#include <limits>
#include <list>
#include <map>
#include <memory>
#include <stdexcept>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>
#include <Eigen/Core>
#include <Eigen/SparseCore>
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/eigen_types.h"
#include "drake/common/polynomial.h"
#include "drake/common/symbolic.h"
#include "drake/solvers/decision_variable.h"
#include "drake/solvers/evaluator_base.h"
#include "drake/solvers/function.h"
namespace drake {
namespace solvers {
// TODO(eric.cousineau): Consider enabling the constraint class directly to
// specify new slack variables.
// TODO(eric.cousineau): Consider parameterized constraints: e.g. the
// acceleration constraints in the rigid body dynamics are constraints
// on vdot and f, but are "parameterized" by q and v.
/**
* A constraint is a function + lower and upper bounds.
*
* Solver interfaces must acknowledge that these constraints are mutable.
* Parameters can change after the constraint is constructed and before the
* call to Solve().
*
* It should support evaluating the constraint, and adding it to an optimization
* problem.
*/
class Constraint : public EvaluatorBase {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Constraint)
/**
* Constructs a constraint which has `num_constraints` rows, with an input
* `num_vars` x 1 vector.
* @param num_constraints. The number of rows in the constraint output.
* @param num_vars. The number of rows in the input.
* If the input dimension is unknown, then set `num_vars` to Eigen::Dynamic.
* @param lb Lower bound, which must be a `num_constraints` x 1 vector.
* @param ub Upper bound, which must be a `num_constraints` x 1 vector.
* @see Eval(...)
*/
template <typename DerivedLB, typename DerivedUB>
Constraint(int num_constraints, int num_vars,
const Eigen::MatrixBase<DerivedLB>& lb,
const Eigen::MatrixBase<DerivedUB>& ub,
const std::string& description = "")
: EvaluatorBase(num_constraints, num_vars, description),
lower_bound_(lb),
upper_bound_(ub) {
check(num_constraints);
}
/**
* Constructs a constraint which has `num_constraints` rows, with an input
* `num_vars` x 1 vector, with no bounds.
* @param num_constraints. The number of rows in the constraint output.
* @param num_vars. The number of rows in the input.
* If the input dimension is unknown, then set `num_vars` to Eigen::Dynamic.
* @see Eval(...)
*/
Constraint(int num_constraints, int num_vars)
: Constraint(
num_constraints, num_vars,
Eigen::VectorXd::Constant(num_constraints,
-std::numeric_limits<double>::infinity()),
Eigen::VectorXd::Constant(
num_constraints, std::numeric_limits<double>::infinity())) {}
/**
* Return whether this constraint is satisfied by the given value, `x`.
* @param x A `num_vars` x 1 vector.
* @param tol A tolerance for bound checking.
*/
bool CheckSatisfied(const Eigen::Ref<const Eigen::VectorXd>& x,
double tol = 1E-6) const {
DRAKE_ASSERT(x.rows() == num_vars() || num_vars() == Eigen::Dynamic);
return DoCheckSatisfied(x, tol);
}
bool CheckSatisfied(const Eigen::Ref<const AutoDiffVecXd>& x,
double tol = 1E-6) const {
DRAKE_ASSERT(x.rows() == num_vars() || num_vars() == Eigen::Dynamic);
return DoCheckSatisfied(x, tol);
}
symbolic::Formula CheckSatisfied(
const Eigen::Ref<const VectorX<symbolic::Variable>>& x) const {
DRAKE_ASSERT(x.rows() == num_vars() || num_vars() == Eigen::Dynamic);
return DoCheckSatisfied(x);
}
const Eigen::VectorXd& lower_bound() const { return lower_bound_; }
const Eigen::VectorXd& upper_bound() const { return upper_bound_; }
/** Number of rows in the output constraint. */
int num_constraints() const { return num_outputs(); }
protected:
/** Updates the lower bound.
* @note if the users want to expose this method in a sub-class, do
* using Constraint::UpdateLowerBound, as in LinearConstraint.
*/
void UpdateLowerBound(const Eigen::Ref<const Eigen::VectorXd>& new_lb) {
if (new_lb.rows() != num_constraints()) {
throw std::logic_error("Lower bound has invalid dimension.");
}
lower_bound_ = new_lb;
}
/** Updates the upper bound.
* @note if the users want to expose this method in a sub-class, do
* using Constraint::UpdateUpperBound, as in LinearConstraint.
*/
void UpdateUpperBound(const Eigen::Ref<const Eigen::VectorXd>& new_ub) {
if (new_ub.rows() != num_constraints()) {
throw std::logic_error("Upper bound has invalid dimension.");
}
upper_bound_ = new_ub;
}
/**
* Set the upper and lower bounds of the constraint.
* @param lower_bound. A `num_constraints` x 1 vector.
* @param upper_bound. A `num_constraints` x 1 vector.
* @note If the users want to expose this method in a sub-class, do
* using Constraint::set_bounds, as in LinearConstraint.
*/
void set_bounds(const Eigen::Ref<const Eigen::VectorXd>& lower_bound,
const Eigen::Ref<const Eigen::VectorXd>& upper_bound) {
UpdateLowerBound(lower_bound);
UpdateUpperBound(upper_bound);
}
virtual bool DoCheckSatisfied(const Eigen::Ref<const Eigen::VectorXd>& x,
const double tol) const {
Eigen::VectorXd y(num_constraints());
DoEval(x, &y);
return (y.array() >= lower_bound_.array() - tol).all() &&
(y.array() <= upper_bound_.array() + tol).all();
}
virtual bool DoCheckSatisfied(const Eigen::Ref<const AutoDiffVecXd>& x,
const double tol) const {
AutoDiffVecXd y(num_constraints());
DoEval(x, &y);
auto get_value = [](const AutoDiffXd& v) { return v.value(); };
return
(y.array().unaryExpr(get_value) >= lower_bound_.array() - tol).all() &&
(y.array().unaryExpr(get_value) <= upper_bound_.array() + tol).all();
}
virtual symbolic::Formula DoCheckSatisfied(
const Eigen::Ref<const VectorX<symbolic::Variable>>& x) const;
private:
void check(int num_constraints) {
static_cast<void>(num_constraints);
DRAKE_ASSERT(lower_bound_.size() == num_constraints &&
"Size of lower bound must match number of constraints.");
DRAKE_ASSERT(upper_bound_.size() == num_constraints &&
"Size of upper bound must match number of constraints.");
}
Eigen::VectorXd lower_bound_;
Eigen::VectorXd upper_bound_;
};
/**
* lb ≤ .5 xᵀQx + bᵀx ≤ ub
* Without loss of generality, the class stores a symmetric matrix Q.
* For a non-symmetric matrix Q₀, we can define Q = (Q₀ + Q₀ᵀ) / 2, since
* xᵀQ₀x = xᵀQ₀ᵀx = xᵀ*(Q₀+Q₀ᵀ)/2 *x. The first equality holds because the
* transpose of a scalar is the scalar itself. Hence we can always convert
* a non-symmetric matrix Q₀ to a symmetric matrix Q.
*/
class QuadraticConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(QuadraticConstraint)
static const int kNumConstraints = 1;
/**
* Construct a quadratic constraint.
* @tparam DerivedQ The type for Q.
* @tparam Derivedb The type for b.
* @param Q0 The square matrix. Notice that Q₀ does not have to be symmetric.
* @param b The linear coefficient.
* @param lb The lower bound.
* @param ub The upper bound.
*/
template <typename DerivedQ, typename Derivedb>
QuadraticConstraint(const Eigen::MatrixBase<DerivedQ>& Q0,
const Eigen::MatrixBase<Derivedb>& b, double lb,
double ub)
: Constraint(kNumConstraints, Q0.rows(), drake::Vector1d::Constant(lb),
drake::Vector1d::Constant(ub)),
Q_((Q0 + Q0.transpose()) / 2),
b_(b) {
DRAKE_ASSERT(Q_.rows() == Q_.cols());
DRAKE_ASSERT(Q_.cols() == b_.rows());
}
~QuadraticConstraint() override {}
/** The symmetric matrix Q, being the Hessian of this constraint.
*/
virtual const Eigen::MatrixXd& Q() const { return Q_; }
virtual const Eigen::VectorXd& b() const { return b_; }
/**
* Updates the quadratic and linear term of the constraint. The new
* matrices need to have the same dimension as before.
* @param new_Q new quadratic term
* @param new_b new linear term
*/
template <typename DerivedQ, typename DerivedB>
void UpdateCoefficients(const Eigen::MatrixBase<DerivedQ>& new_Q,
const Eigen::MatrixBase<DerivedB>& new_b) {
if (new_Q.rows() != new_Q.cols() || new_Q.rows() != new_b.rows() ||
new_b.cols() != 1) {
throw std::runtime_error("New constraints have invalid dimensions");
}
if (new_b.rows() != b_.rows()) {
throw std::runtime_error("Can't change the number of decision variables");
}
Q_ = (new_Q + new_Q.transpose()) / 2;
b_ = new_b;
}
private:
template <typename DerivedX, typename ScalarY>
void DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<ScalarY>* y) const;
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
Eigen::MatrixXd Q_;
Eigen::VectorXd b_;
};
/**
Constraining the linear expression \f$ z=Ax+b \f$ lies within the Lorentz cone.
A vector z ∈ ℝ ⁿ lies within Lorentz cone if
@f[
z_0 \ge \sqrt{z_1^2+...+z_{n-1}^2}
@f]
<!-->
z₀ ≥ sqrt(z₁² + ... + zₙ₋₁²)
<-->
where A ∈ ℝ ⁿˣᵐ, b ∈ ℝ ⁿ are given matrices.
Ideally this constraint should be handled by a second-order cone solver.
In case the user wants to enforce this constraint through general nonlinear
optimization, with smooth gradient, we alternatively impose the following
constraint, with smooth gradient everywhere
@f[
a_0^Tx+b_0\ge 0\\
(a_0^Tx+b_0)^2-(a_1^Tx+b_1)^2-...-(a_{n-1}^Tx+b_{n-1})^2 \ge 0
@f]
where @f$ a_i^T@f$ is the i'th row of matrix @f$ A@f$. @f$ b_i @f$ is the i'th
entry of vector @f$ b @f$.
For more information and visualization, please refer to
https://inst.eecs.berkeley.edu/~ee127a/book/login/l_socp_soc.html
*/
class LorentzConeConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LorentzConeConstraint)
LorentzConeConstraint(const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b)
: Constraint(
2, A.cols(), Eigen::Vector2d::Constant(0.0),
Eigen::Vector2d::Constant(std::numeric_limits<double>::infinity())),
A_(A),
b_(b) {
DRAKE_DEMAND(A_.rows() >= 2);
DRAKE_ASSERT(A_.rows() == b_.rows());
}
~LorentzConeConstraint() override {}
/** Getter for A. */
const Eigen::MatrixXd& A() const { return A_; }
/** Getter for b. */
const Eigen::VectorXd& b() const { return b_; }
private:
template <typename DerivedX, typename ScalarY>
void DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<ScalarY>* y) const;
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
const Eigen::MatrixXd A_;
const Eigen::VectorXd b_;
};
/**
* Constraining that the linear expression \f$ z=Ax+b \f$ lies within rotated
* Lorentz cone.
* A vector z ∈ ℝ ⁿ lies within rotated Lorentz cone, if
* @f[
* z_0 \ge 0\\
* z_1 \ge 0\\
* z_0 z_1 \ge z_2^2 + z_3^2 + ... + z_{n-1}^2
* @f]
* where A ∈ ℝ ⁿˣᵐ, b ∈ ℝ ⁿ are given matrices.
* <!-->
* z₀ ≥ 0
* z₁ ≥ 0
* z₀ * z₁ ≥ z₂² + z₃² + ... zₙ₋₁²
* <-->
* For more information and visualization, please refer to
* https://inst.eecs.berkeley.edu/~ee127a/book/login/l_socp_soc.html
*/
class RotatedLorentzConeConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(RotatedLorentzConeConstraint)
RotatedLorentzConeConstraint(const Eigen::Ref<const Eigen::MatrixXd>& A,
const Eigen::Ref<const Eigen::VectorXd>& b)
: Constraint(
3, A.cols(), Eigen::Vector3d::Constant(0.0),
Eigen::Vector3d::Constant(std::numeric_limits<double>::infinity())),
A_(A),
b_(b) {
DRAKE_DEMAND(A_.rows() >= 3);
DRAKE_ASSERT(A_.rows() == b_.rows());
}
/** Getter for A. */
const Eigen::MatrixXd& A() const { return A_; }
/** Getter for b. */
const Eigen::VectorXd& b() const { return b_; }
~RotatedLorentzConeConstraint() override {}
private:
template <typename DerivedX, typename ScalarY>
void DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<ScalarY>* y) const;
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
const Eigen::MatrixXd A_;
const Eigen::VectorXd b_;
};
/**
* A constraint that may be specified using another (potentially nonlinear)
* evaluator.
* @tparam EvaluatorType The nested evaluator.
*/
template <typename EvaluatorType = EvaluatorBase>
class EvaluatorConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(EvaluatorConstraint)
/**
* Constructs an evaluator constraint, given the EvaluatorType instance
* (which will specify the number of constraints and variables), and will
* forward the remaining arguments to the Constraint constructor.
* @param evaluator EvaluatorType instance.
* @param args Arguments to be forwarded to the constraint constructor.
*/
template <typename... Args>
EvaluatorConstraint(const std::shared_ptr<EvaluatorType>& evaluator,
Args&&... args)
: Constraint(evaluator->num_outputs(), evaluator->num_vars(),
std::forward<Args>(args)...),
evaluator_(evaluator) {}
using Constraint::set_bounds;
using Constraint::UpdateLowerBound;
using Constraint::UpdateUpperBound;
protected:
/** Reference to the nested evaluator. */
const EvaluatorType& evaluator() const { return *evaluator_; }
private:
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override {
evaluator_->Eval(x, y);
}
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override {
evaluator_->Eval(x, y);
}
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override {
evaluator_->Eval(x, y);
}
std::shared_ptr<EvaluatorType> evaluator_;
};
/**
* lb[i] <= P[i](x, y...) <= ub[i], where each P[i] is a multivariate
* polynomial in x, y...
*
* A constraint on the values of multivariate polynomials.
*
* The Polynomial class uses a different variable naming scheme; thus the
* caller must provide a list of Polynomial::VarType variables that correspond
* to the members of the MathematicalProgram::Binding (the individual scalar
* elements of the given VariableList).
*/
class PolynomialConstraint : public EvaluatorConstraint<PolynomialEvaluator> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(PolynomialConstraint)
/**
* Constructs a polynomial constraint
* @param polynomials Polynomial vector, a `num_constraints` x 1 vector.
* @param poly_vars Polynomial variables, a `num_vars` x 1 vector.
* @param lb Lower bounds, a `num_constraints` x 1 vector.
* @param ub Upper bounds, a `num_constraints` x 1 vector.
*/
PolynomialConstraint(const VectorXPoly& polynomials,
const std::vector<Polynomiald::VarType>& poly_vars,
const Eigen::VectorXd& lb, const Eigen::VectorXd& ub)
: EvaluatorConstraint(
std::make_shared<PolynomialEvaluator>(polynomials, poly_vars), lb,
ub) {}
~PolynomialConstraint() override {}
const VectorXPoly& polynomials() const { return evaluator().polynomials(); }
const std::vector<Polynomiald::VarType>& poly_vars() const {
return evaluator().poly_vars();
}
};
// TODO(bradking): consider implementing DifferentiableConstraint,
// TwiceDifferentiableConstraint, ComplementarityConstraint,
// IntegerConstraint, ...
/**
* Implements a constraint of the form @f$ lb <= Ax <= ub @f$
*/
class LinearConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LinearConstraint)
template <typename DerivedA, typename DerivedLB, typename DerivedUB>
LinearConstraint(const Eigen::MatrixBase<DerivedA>& a,
const Eigen::MatrixBase<DerivedLB>& lb,
const Eigen::MatrixBase<DerivedUB>& ub)
: Constraint(a.rows(), a.cols(), lb, ub), A_(a) {
DRAKE_ASSERT(a.rows() == lb.rows());
}
~LinearConstraint() override {}
virtual Eigen::SparseMatrix<double> GetSparseMatrix() const {
// TODO(eric.cousineau): Consider storing or caching sparse matrix, such
// that we can return a const lvalue reference.
return A_.sparseView();
}
virtual const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>& A()
const {
return A_;
}
/**
* Updates the linear term, upper and lower bounds in the linear constraint.
* The updated constraint is:
* new_lb <= new_A * x <= new_ub
* Note that the size of constraints (number of rows) can change, but the
* number of variables (number of cols) cannot.
* @param new_A new linear term
* @param new_lb new lower bound
* @param new_up new upper bound
*/
template <typename DerivedA, typename DerivedL, typename DerivedU>
void UpdateCoefficients(const Eigen::MatrixBase<DerivedA>& new_A,
const Eigen::MatrixBase<DerivedL>& new_lb,
const Eigen::MatrixBase<DerivedU>& new_ub) {
if (new_A.rows() != new_lb.rows() || new_lb.rows() != new_ub.rows() ||
new_lb.cols() != 1 || new_ub.cols() != 1) {
throw std::runtime_error("New constraints have invalid dimensions");
}
if (new_A.cols() != A_.cols()) {
throw std::runtime_error("Can't change the number of decision variables");
}
A_ = new_A;
set_num_outputs(A_.rows());
set_bounds(new_lb, new_ub);
}
using Constraint::set_bounds;
using Constraint::UpdateLowerBound;
using Constraint::UpdateUpperBound;
protected:
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> A_;
private:
template <typename DerivedX, typename ScalarY>
void DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<ScalarY>* y) const;
};
/**
* Implements a constraint of the form @f$ Ax = b @f$
*/
class LinearEqualityConstraint : public LinearConstraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LinearEqualityConstraint)
template <typename DerivedA, typename DerivedB>
LinearEqualityConstraint(const Eigen::MatrixBase<DerivedA>& Aeq,
const Eigen::MatrixBase<DerivedB>& beq)
: LinearConstraint(Aeq, beq, beq) {}
LinearEqualityConstraint(const Eigen::Ref<const Eigen::RowVectorXd>& a,
double beq)
: LinearEqualityConstraint(a, Vector1d(beq)) {}
~LinearEqualityConstraint() override {}
/*
* @brief change the parameters of the constraint (A and b), but not the
*variable associations
*
* note that A and b can change size in the rows only (representing a
*different number of linear constraints, but on the same decision variables)
*/
template <typename DerivedA, typename DerivedB>
void UpdateCoefficients(const Eigen::MatrixBase<DerivedA>& Aeq,
const Eigen::MatrixBase<DerivedB>& beq) {
LinearConstraint::UpdateCoefficients(Aeq, beq, beq);
}
private:
/**
* The user should not call this function. Call UpdateCoefficients(Aeq, beq)
* instead.
*/
template <typename DerivedA, typename DerivedL, typename DerivedU>
void UpdateCoefficients(const Eigen::MatrixBase<DerivedA>&,
const Eigen::MatrixBase<DerivedL>&,
const Eigen::MatrixBase<DerivedU>&) {
static_assert(
!std::is_same<DerivedA, DerivedA>::value,
"This method should not be called form `LinearEqualityConstraint`");
}
};
/**
* Implements a constraint of the form @f$ lb <= x <= ub @f$
*
* Note: the base Constraint class (as implemented at the moment) could
* play this role. But this class enforces that it is ONLY a bounding
* box constraint, and not something more general. Some solvers use
* this information to handle bounding box constraints differently than
* general constraints, so use of this form is encouraged.
*/
class BoundingBoxConstraint : public LinearConstraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(BoundingBoxConstraint)
template <typename DerivedLB, typename DerivedUB>
BoundingBoxConstraint(const Eigen::MatrixBase<DerivedLB>& lb,
const Eigen::MatrixBase<DerivedUB>& ub)
: LinearConstraint(Eigen::MatrixXd::Identity(lb.rows(), lb.rows()), lb,
ub) {}
~BoundingBoxConstraint() override {}
private:
template <typename DerivedX, typename ScalarY>
void DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<ScalarY>* y) const;
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
};
/**
* Implements a constraint of the form:
*
* <pre>
* Mx + q >= 0
* x >= 0
* x'(Mx + q) == 0
* </pre>
*
* An implied slack variable complements any 0 component of x. To get
* the slack values at a given solution x, use Eval(x).
*/
class LinearComplementarityConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LinearComplementarityConstraint)
template <typename DerivedM, typename Derivedq>
LinearComplementarityConstraint(const Eigen::MatrixBase<DerivedM>& M,
const Eigen::MatrixBase<Derivedq>& q)
: Constraint(q.rows(), M.cols()), M_(M), q_(q) {}
~LinearComplementarityConstraint() override {}
const Eigen::MatrixXd& M() const { return M_; }
const Eigen::VectorXd& q() const { return q_; }
protected:
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
bool DoCheckSatisfied(const Eigen::Ref<const Eigen::VectorXd>& x,
const double tol) const override;
bool DoCheckSatisfied(const Eigen::Ref<const AutoDiffVecXd>& x,
const double tol) const override;
symbolic::Formula DoCheckSatisfied(
const Eigen::Ref<const VectorX<symbolic::Variable>>& x) const override;
private:
// Return Mx + q (the value of the slack variable).
template <typename DerivedX, typename ScalarY>
void DoEvalGeneric(const Eigen::MatrixBase<DerivedX>& x,
VectorX<ScalarY>* y) const;
// TODO(ggould-tri) We are storing what are likely statically sized matrices
// in dynamically allocated containers. This probably isn't optimal.
Eigen::MatrixXd M_;
Eigen::VectorXd q_;
};
/**
* Implements a positive semidefinite constraint on a symmetric matrix S
* @f[\text{
* S is p.s.d
* }@f]
* namely, all eigen values of S are non-negative.
*/
class PositiveSemidefiniteConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(PositiveSemidefiniteConstraint)
/**
* Impose the constraint that a symmetric matrix with size @p rows x @p rows
* is positive semidefinite.
* @see MathematicalProgram::AddPositiveSemidefiniteConstraint() for how
* to use this constraint on some decision variables. We currently use this
* constraint as a place holder in MathematicalProgram, to indicate the
* positive semidefiniteness of some decision variables.
* @param rows The number of rows (and columns) of the symmetric matrix.
*
* Example:
* @code{.cc}
* // Create a MathematicalProgram object.
* auto prog = MathematicalProgram();
*
* // Add a 2 x 2 symmetric matrix S to optimization program as new decision
* // variables.
* auto S = prog.NewSymmetricContinuousVariables<2>("S");
*
* // Impose a positive semidefinite constraint on S.
* std::shared_ptr<PositiveSemidefiniteConstraint> psd_constraint =
* prog.AddPositiveSemidefiniteConstraint(S);
*
* /////////////////////////////////////////////////////////////
* // Add more constraints to make the program more interesting,
* // but this is not needed.
*
* // Add the constraint that S(1, 0) = 1.
* prog.AddBoundingBoxConstraint(1, 1, S(1, 0));
*
* // Minimize S(0, 0) + S(1, 1).
* prog.AddLinearCost(Eigen::RowVector2d(1, 1), {S.diagonal()});
*
* /////////////////////////////////////////////////////////////
*
* // Now solve the program.
* auto result = Solve(prog);
*
* // Retrieve the solution of matrix S.
* auto S_value = GetSolution(S, result);
*
* // Compute the eigen values of the solution, to see if they are
* // all non-negative.
* Eigen::Vector4d S_stacked;
* S_stacked << S_value.col(0), S_value.col(1);
*
* Eigen::VectorXd S_eigen_values;
* psd_constraint->Eval(S_stacked, S_eigen_values);
*
* std::cout<<"S solution is: " << S << std::endl;
* std::cout<<"The eigen value of S is " << S_eigen_values << std::endl;
* @endcode
*/
explicit PositiveSemidefiniteConstraint(int rows)
: Constraint(rows, rows * rows, Eigen::VectorXd::Zero(rows),
Eigen::VectorXd::Constant(
rows, std::numeric_limits<double>::infinity())),
matrix_rows_(rows) {}
~PositiveSemidefiniteConstraint() override {}
int matrix_rows() const { return matrix_rows_; }
protected:
/**
* Evaluate the eigen values of the symmetric matrix.
* @param x The stacked columns of the symmetric matrix.
*/
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
/**
* @param x The stacked columns of the symmetric matrix. This function is not
* supported yet, since Eigen's eigen value solver does not accept
* AutoDiffScalar.
*/
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
/**
* @param x The stacked columns of the symmetric matrix. This function is not
* supported, since Eigen's eigen value solver does not accept
* symbolic::Expression.
*/
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
private:
int matrix_rows_; // Number of rows in the symmetric matrix being positive
// semi-definite.
};
/**
* Impose the matrix inequality constraint on variable x
* <!-->
* F₀ + x₁ * F₁ + ... xₙ * Fₙ is p.s.d
* <-->
* @f[
* F_0 + x_1 F_1 + ... + x_n F_n \text{ is p.s.d}
* @f]
* where p.s.d stands for positive semidefinite.
* @f$ F_0, F_1, ..., F_n @f$ are all given symmetric matrices of the same size.
*/
class LinearMatrixInequalityConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LinearMatrixInequalityConstraint)
/**
* @param F Each symmetric matrix F[i] should be of the same size.
* @param symmetry_tolerance The precision to determine if the input matrices
* Fi are all symmetric. @see math::IsSymmetric().
*/
LinearMatrixInequalityConstraint(
const std::vector<Eigen::Ref<const Eigen::MatrixXd>>& F,
double symmetry_tolerance = 1E-10);
~LinearMatrixInequalityConstraint() override {}
/* Getter for all given matrices F */
const std::vector<Eigen::MatrixXd>& F() const { return F_; }
/// Gets the number of rows in the matrix inequality constraint. Namely
/// Fi are all matrix_rows() x matrix_rows() matrices.
int matrix_rows() const { return matrix_rows_; }
protected:
/**
* Evaluate the eigen values of the linear matrix.
*/
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
/**
* This function is not supported, since Eigen's eigen value solver does not
* accept AutoDiffScalar type.
*/
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
/**
* This function is not supported, since Eigen's eigen value solver does not
* accept symbolic::Expression type.
*/
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
private:
std::vector<Eigen::MatrixXd> F_;
const int matrix_rows_{};
};
/**
* Impose a generic (potentially nonlinear) constraint represented as a
* vector of symbolic Expression. Expression::Evaluate is called on every
* constraint evaluation.
*
* Uses symbolic::Jacobian to provide the gradients to the AutoDiff method.
*/
class ExpressionConstraint : public Constraint {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(ExpressionConstraint)
ExpressionConstraint(const Eigen::Ref<const VectorX<symbolic::Expression>>& v,
const Eigen::Ref<const Eigen::VectorXd>& lb,
const Eigen::Ref<const Eigen::VectorXd>& ub);
/**
* @return the list of the variables involved in the vector of expressions,
* in the order that they are expected to be received during DoEval.
* Any Binding that connects this constraint to decision variables should
* pass this list of variables to the Binding.
*/
const VectorXDecisionVariable& vars() const { return vars_; }
/** @return the symbolic expressions. */
const VectorX<symbolic::Expression>& expressions() const {
return expressions_;
}
protected:
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
Eigen::VectorXd* y) const override;
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
AutoDiffVecXd* y) const override;
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>& x,
VectorX<symbolic::Expression>* y) const override;
private:
VectorX<symbolic::Expression> expressions_{0};
MatrixX<symbolic::Expression> derivatives_{0, 0};
// map_var_to_index_[vars_(i).get_id()] = i.
VectorXDecisionVariable vars_{0};
std::unordered_map<symbolic::Variable::Id, int> map_var_to_index_;
// Only for caching, does not carrying hidden state.
mutable symbolic::Environment environment_;
};
} // namespace solvers
} // namespace drake