forked from sammy-tri/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mathematical_program.h
3116 lines (2896 loc) · 118 KB
/
mathematical_program.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
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#pragma once
#include <array>
#include <cstddef>
#include <iostream>
#include <limits>
#include <list>
#include <map>
#include <memory>
#include <set>
#include <stdexcept>
#include <string>
#include <type_traits>
#include <unordered_map>
#include <utility>
#include <vector>
#include <Eigen/Core>
#include "drake/common/autodiff.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/drake_optional.h"
#include "drake/common/eigen_types.h"
#include "drake/common/polynomial.h"
#include "drake/common/symbolic.h"
#include "drake/solvers/binding.h"
#include "drake/solvers/constraint.h"
#include "drake/solvers/cost.h"
#include "drake/solvers/create_constraint.h"
#include "drake/solvers/create_cost.h"
#include "drake/solvers/decision_variable.h"
#include "drake/solvers/function.h"
#include "drake/solvers/indeterminate.h"
#include "drake/solvers/program_attribute.h"
#include "drake/solvers/solution_result.h"
#include "drake/solvers/solver_interface.h"
#include "drake/solvers/solver_options.h"
#include "drake/solvers/solver_result.h"
namespace drake {
namespace solvers {
class SolverInterface;
/** @addtogroup solvers
* @{
* Drake wraps a number of commercial solvers (+ a few custom solvers) to
* provide a common interface for convex optimization, mixed-integer convex
* optimization, and other non-convex mathematical programs.
*
* The MathematicalProgram class handles the coordination of decision variables,
* objectives, and constraints. The MathematicalProgram::Solve() method
* reflects on the accumulated objectives and constraints and will dispatch to
* the most appropriate solver. Alternatively, one can invoke specific solver
* by instantiating its SolverInterface and passing the MathematicalProgram
* directly to the SolverInterface::Solve() method.
*
* Our solver coverage still has many gaps, but is under active development.
*
* <b>Closed-form solutions</b>
*
* The LinearSystemSolver and EqualityConstrainedQPSolver classes provide
* efficient closed-form solutions to these special cases.
*
* <b>Convex Optimization</b>
*
* <table>
* <tr>
* <td>Solver</td>
* <td><a href="https://en.wikipedia.org/wiki/Linear_programming">LP</a></td>
* <td><a href="https://en.wikipedia.org/wiki/Quadratic_programming">
* QP</a></td>
* <td><a href="https://en.wikipedia.org/wiki/Second-order_cone_programming">
* SOCP</a></td>
* <td><a href="https://en.wikipedia.org/wiki/Semidefinite_programming">
* SDP</a></td>
* <td><a href="https://en.wikipedia.org/wiki/Sum-of-squares_optimization">
* SOS</a></td>
* </tr>
* <tr><td>† <a href="https://www.gurobi.com/products/gurobi-optimizer">
* Gurobi</a></td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td></td>
* <td></td>
* </tr>
* <tr><td>† <a href="https://www.mosek.com/products/mosek">
* Mosek</a></td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* </tr>
* <tr><td> <a href="https://github.com/cvxgrp/scs">
* SCS</a></td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* </tr>
* <tr><td> <a href="https://github.com/oxfordcontrol/osqp">
* OSQP</a></td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td></td>
* <td></td>
* <td></td>
* </tr>
* </table>
*
* <b>Mixed-Integer Convex Optimization</b>
*
* <table>
* <tr>
* <td>Solver</td>
* <td>MILP</a></td>
* <td>MIQP</a></td>
* <td>MISOCP</a></td>
* <td>MISDP</a></td>
* </tr>
* <tr><td>† <a href="https://www.gurobi.com/products/gurobi-optimizer">
* Gurobi</a></td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td></td>
* </tr>
* <tr><td>† <a href="https://www.mosek.com/products/mosek">
* Mosek</a></td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td align="center">♦</td>
* <td></td>
* </tr>
* </table>
*
* <b>Nonconvex Programming</b>
*
* <table>
* <tr>
* <td>Solver</td>
* <td><a href="https://en.wikipedia.org/wiki/Nonlinear_programming">
* Nonlinear Program</a></td>
* <td><a href="https://en.wikipedia.org/wiki/Linear_complementarity_problem">
* LCP</a></td>
* <td><a href="https://en.wikipedia.org/wiki/Satisfiability_modulo_theories">
* SMT</a></td>
* </tr>
* <tr><td>†
* <a href="http://www.sbsi-sol-optimize.com/asp/sol_product_snopt.htm">
* SNOPT</a></td></tr>
* <td align="center">♦</td>
* <td></td>
* <td></td>
* <tr><td><a href="https://projects.coin-or.org/Ipopt">Ipopt</a></td></tr>
* <td align="center">♦</td>
* <td></td>
* <td></td>
* <tr><td><a href="http://ab-initio.mit.edu/wiki/index.php/NLopt">
* NLopt</a></td></tr>
* <td align="center">♦</td>
* <td></td>
* <td></td>
* <tr><td><a href="https://github.com/PositronicsLab/Moby">
* Moby LCP</a></td>
* <td></td>
* <td align="center">♦</td>
* <td></td>
* <tr><td><a href="https://dreal.github.io/">dReal</a></td>
* <td></td>
* <td></td>
* <td align="center">♦</td>
* </tr>
* </table>
*
* † indicates that this is a commercial solver which requires a license
* (note that some have free licenses for academics).
* @}
*/
class MathematicalProgram;
template <int...>
struct NewVariableNames {};
/**
* The type of the names for the newly added variables.
* @tparam Size If Size is a fixed non-negative integer, then the type of the
* name is std::array<std::string, Size>. Otherwise the type is
* std::vector<std::string>.
*/
template <int Size>
struct NewVariableNames<Size> {
typedef std::array<std::string, Size> type;
};
template <>
struct NewVariableNames<Eigen::Dynamic> {
typedef std::vector<std::string> type;
};
template <int Rows, int Cols>
struct NewVariableNames<Rows, Cols>
: public NewVariableNames<MultiplyEigenSizes<Rows, Cols>::value> {};
template <int Rows>
struct NewSymmetricVariableNames
: public NewVariableNames<Rows == Eigen::Dynamic ? Eigen::Dynamic
: Rows*(Rows + 1) / 2> {};
namespace internal {
/**
* Return un-initialized new variable names.
*/
template <int Size>
typename std::enable_if<Size >= 0, typename NewVariableNames<Size>::type>::type
CreateNewVariableNames(int) {
typename NewVariableNames<Size>::type names;
return names;
}
/**
* Return un-initialized new variable names.
*/
template <int Size>
typename std::enable_if<Size == Eigen::Dynamic,
typename NewVariableNames<Size>::type>::type
CreateNewVariableNames(int size) {
typename NewVariableNames<Eigen::Dynamic>::type names(size);
return names;
}
/**
* Set the names of the newly added variables.
* @param name The common name of all new variables.
* @param rows The number of rows in the new variables.
* @param cols The number of columns in the new variables.
* @pre The size of @p names is @p rows * @p cols.
*/
template <typename Derived>
void SetVariableNames(const std::string& name, int rows, int cols,
Derived* names) {
DRAKE_DEMAND(static_cast<int>(names->size()) == rows * cols);
if (cols == 1) {
for (int i = 0; i < rows; ++i) {
(*names)[i] = name + "(" + std::to_string(i) + ")";
}
} else {
for (int j = 0; j < cols; ++j) {
for (int i = 0; i < rows; ++i) {
(*names)[j * rows + i] =
name + "(" + std::to_string(i) + "," + std::to_string(j) + ")";
}
}
}
}
} // namespace internal
namespace detail {
/**
* Template condition to only catch when Constraints are inadvertently passed
* as an argument. If the class is binding-compatible with a Constraint, then
* this will provide a static assertion to enable easier debugging of which
* type failed.
* @tparam F The type to be tested.
* @see http://stackoverflow.com/a/13366183/7829525
*/
template <typename F>
struct assert_if_is_constraint {
static constexpr bool value = is_binding_compatible<F, Constraint>::value;
// Use deferred evaluation
static_assert(
!value,
"You cannot pass a Constraint to create a Cost object from a function. "
"Please ensure you are passing a Cost.");
};
} // namespace detail
/**
* MathematicalProgram stores the decision variables, the constraints and costs
* of an optimization problem. The user can solve the problem by calling Solve()
* function, and obtain the results of the optimization.
*
* @ingroup solvers
*/
class MathematicalProgram {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MathematicalProgram)
using VarType = symbolic::Variable::Type;
/// The optimal cost is +∞ when the problem is globally infeasible.
static constexpr double kGlobalInfeasibleCost =
std::numeric_limits<double>::infinity();
/// The optimal cost is -∞ when the problem is unbounded.
static constexpr double kUnboundedCost =
-std::numeric_limits<double>::infinity();
MathematicalProgram();
virtual ~MathematicalProgram();
/** Clones an optimization program.
* The clone will be functionally equivalent to the source program with the
* same:
*
* - decision variables
* - constraints
* - costs
* - solver settings
* - initial guess
*
* However, the clone's x values will be initialized to NaN, and all internal
* solvers will be freshly constructed.
* @retval new_prog. The newly constructed mathematical program.
*/
std::unique_ptr<MathematicalProgram> Clone() const;
/**
* Adds continuous variables, appending them to an internal vector of any
* existing vars.
* The initial guess values for the new variables are set to NaN, to
* indicate that an initial guess has not been assigned.
* Callers are expected to add costs
* and/or constraints to have any effect during optimization.
* Callers can also set the initial guess of the decision variables through
* SetInitialGuess() or SetInitialGuessForAllVariables().
* @param rows The number of rows in the new variables.
* @param name The name of the newly added variables
* @return The VectorDecisionVariable of size rows x 1, containing the new
* vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* auto x = prog.NewContinuousVariables(2, "x");
* @endcode
* This adds a 2 x 1 vector containing decision variables into the program.
* The names of the variables are "x(0)" and "x(1)".
*
* The name of the variable is only used for the user in order to ease
* readability.
*/
VectorXDecisionVariable NewContinuousVariables(
int rows, const std::string& name = "x") {
return NewContinuousVariables<Eigen::Dynamic, 1>(rows, 1, name);
}
/**
* Adds continuous variables, appending them to an internal vector of any
* existing vars.
* The initial guess values for the new variables are set to NaN, to
* indicate that an initial guess has not been assigned.
* Callers are expected to add costs
* and/or constraints to have any effect during optimization.
* Callers can also set the initial guess of the decision variables through
* SetInitialGuess() or SetInitialGuessForAllVariables().
* @tparam Rows The number of rows of the new variables, in the compile time.
* @tparam Cols The number of columns of the new variables, in the compile
* time.
* @param rows The number of rows in the new variables. When Rows is not
* Eigen::Dynamic, rows is ignored.
* @param cols The number of columns in the new variables. When Cols is not
* Eigen::Dynamic, cols is ignored.
* @param name All variables will share the same name, but different index.
* @return The MatrixDecisionVariable of size Rows x Cols, containing the new
* vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* auto x = prog.NewContinuousVariables(2, 3, "X");
* auto y = prog.NewContinuousVariables<2, 3>(2, 3, "X");
* @endcode
* This adds a 2 x 3 matrix decision variables into the program.
*
* The name of the variable is only used for the user in order to ease
* readability.
*/
template <int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
MatrixDecisionVariable<Rows, Cols> NewContinuousVariables(
int rows, int cols, const std::string& name = "X") {
rows = Rows == Eigen::Dynamic ? rows : Rows;
cols = Cols == Eigen::Dynamic ? cols : Cols;
auto names =
internal::CreateNewVariableNames<MultiplyEigenSizes<Rows, Cols>::value>(
rows * cols);
internal::SetVariableNames(name, rows, cols, &names);
return NewVariables<Rows, Cols>(VarType::CONTINUOUS, names, rows, cols);
}
/**
* Adds continuous variables, appending them to an internal vector of any
* existing vars.
* The initial guess values for the new variables are set to NaN, to
* indicate that an initial guess has not been assigned.
* Callers are expected to add costs
* and/or constraints to have any effect during optimization.
* Callers can also set the initial guess of the decision variables through
* SetInitialGuess() or SetInitialGuessForAllVariables().
* @tparam Rows The number of rows in the new variables.
* @tparam Cols The number of columns in the new variables. The default is 1.
* @param name All variables will share the same name, but different index.
* @return The MatrixDecisionVariable of size rows x cols, containing the new
* vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* auto x = prog.NewContinuousVariables<2, 3>("X");
* @endcode
* This adds a 2 x 3 matrix decision variables into the program.
*
* The name of the variable is only used for the user in order to ease
* readability.
*/
template <int Rows, int Cols = 1>
MatrixDecisionVariable<Rows, Cols> NewContinuousVariables(
const std::string& name = "X") {
return NewContinuousVariables<Rows, Cols>(Rows, Cols, name);
}
/**
* Adds binary variables, appending them to an internal vector of any
* existing vars.
* The initial guess values for the new variables are set to NaN, to
* indicate that an initial guess has not been assigned.
* Callers are expected to add costs
* and/or constraints to have any effect during optimization.
* Callers can also set the initial guess of the decision variables through
* SetInitialGuess() or SetInitialGuessForAllVariables().
* @tparam Rows The number of rows in the new variables.
* @tparam Cols The number of columns in the new variables.
* @param rows The number of rows in the new variables.
* @param cols The number of columns in the new variables.
* @param name The commonly shared name of the new variables.
* @return The MatrixDecisionVariable of size rows x cols, containing the new
* vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* auto b = prog.NewBinaryVariables(2, 3, "b");
* @endcode
* This adds a 2 x 3 matrix decision variables into the program.
*
* The name of the variable is only used for the user in order to ease
* readability.
*/
template <int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
MatrixDecisionVariable<Rows, Cols> NewBinaryVariables(
int rows, int cols, const std::string& name) {
rows = Rows == Eigen::Dynamic ? rows : Rows;
cols = Cols == Eigen::Dynamic ? cols : Cols;
auto names =
internal::CreateNewVariableNames<MultiplyEigenSizes<Rows, Cols>::value>(
rows * cols);
internal::SetVariableNames(name, rows, cols, &names);
return NewVariables<Rows, Cols>(VarType::BINARY, names, rows, cols);
}
/**
* Adds a matrix of binary variables into the optimization program.
* @tparam Rows The number of rows in the newly added binary variables.
* @tparam Cols The number of columns in the new variables. The default is 1.
* @param name Each newly added binary variable will share the same name. The
* default name is "b".
* @return A matrix containing the newly added variables.
*/
template <int Rows, int Cols = 1>
MatrixDecisionVariable<Rows, Cols> NewBinaryVariables(
const std::string& name = "b") {
return NewBinaryVariables<Rows, Cols>(Rows, Cols, name);
}
/**
* Adds binary variables to this MathematicalProgram. The new variables are
* viewed as a column vector, with size @p rows x 1.
* @see NewBinaryVariables(int rows, int cols, const
* std::vector<std::string>& names);
*/
VectorXDecisionVariable NewBinaryVariables(int rows,
const std::string& name = "b") {
return NewBinaryVariables<Eigen::Dynamic, 1>(rows, 1, name);
}
/**
* Adds a runtime sized symmetric matrix as decision variables to
* this MathematicalProgram.
* The optimization will only use the stacked columns of the
* lower triangular part of the symmetric matrix as decision variables.
* @param rows The number of rows in the symmetric matrix.
* @param name The name of the matrix. It is only used the for user to
* understand the optimization program. The default name is "Symmetric", and
* each variable will be named as
* <pre>
* Symmetric(0, 0) Symmetric(1, 0) ... Symmetric(rows-1, 0)
* Symmetric(1, 0) Symmetric(1, 1) ... Symmetric(rows-1, 1)
* ...
* Symmetric(rows-1,0) Symmetric(rows-1,1) ... Symmetric(rows-1, rows-1)
* </pre>
* Notice that the (i,j)'th entry and (j,i)'th entry has the same name.
* @return The newly added decision variables.
*/
MatrixXDecisionVariable NewSymmetricContinuousVariables(
int rows, const std::string& name = "Symmetric");
/**
* Adds a static sized symmetric matrix as decision variables to
* this MathematicalProgram.
* The optimization will only use the stacked columns of the
* lower triangular part of the symmetric matrix as decision variables.
* @tparam rows The number of rows in the symmetric matrix.
* @param name The name of the matrix. It is only used the for user to
* understand the optimization program. The default name is "Symmetric", and
* each variable will be named as
* <pre>
* Symmetric(0, 0) Symmetric(1, 0) ... Symmetric(rows-1, 0)
* Symmetric(1, 0) Symmetric(1, 1) ... Symmetric(rows-1, 1)
* ...
* Symmetric(rows-1,0) Symmetric(rows-1,1) ... Symmetric(rows-1, rows-1)
* </pre>
* Notice that the (i,j)'th entry and (j,i)'th entry has the same name.
* @return The newly added decision variables.
*/
template <int rows>
MatrixDecisionVariable<rows, rows> NewSymmetricContinuousVariables(
const std::string& name = "Symmetric") {
typename NewSymmetricVariableNames<rows>::type names;
int var_count = 0;
for (int j = 0; j < static_cast<int>(rows); ++j) {
for (int i = j; i < static_cast<int>(rows); ++i) {
names[var_count] =
name + "(" + std::to_string(i) + "," + std::to_string(j) + ")";
++var_count;
}
}
return NewSymmetricVariables<rows>(VarType::CONTINUOUS, names);
}
/** Appends new variables to the end of the existing variables.
* @param decision_variables The newly added decision_variables.
* @pre `decision_variables` should not intersect with the existing variables
* or indeterminates in the optimization program.
* @pre Each entry in `decision_variables` should not be a dummy variable.
* @throws std::runtime_error if the preconditions are not satisfied.
*/
void AddDecisionVariables(
const Eigen::Ref<const VectorXDecisionVariable>& decision_variables);
/**
* Returns a free polynomial in a monomial basis over @p indeterminates of a
* given @p degree. It uses @p coeff_name to make new decision variables and
* use them as coefficients. For example, `NewFreePolynomial({x₀, x₁}, 2)`
* returns a₀x₁² + a₁x₀x₁ + a₂x₀² + a₃x₁ + a₄x₀ + a₅.
*/
symbolic::Polynomial NewFreePolynomial(
const symbolic::Variables& indeterminates, int degree,
const std::string& coeff_name = "a");
/**
* Types of non-negative polynomial that can be found through conic
* optimization. We currently support SOS, SDSOS and DSOS. For more
* information about these polynomial types, please refer to
* "DSOS and SDSOS Optimization: More Tractable
* Alternatives to Sum of Squares and Semidefinite Optimization" by Amir Ali
* Ahmadi and Anirudha Majumdar, with arXiv link
* https://arxiv.org/abs/1706.02586
*/
enum class NonnegativePolynomial {
kSos, ///< A sum-of-squares polynomial.
kSdsos, ///< A scaled-diagonally dominant sum-of-squares polynomial.
kDsos, ///< A diagonally dominant sum-of-squares polynomial.
};
/**
* Returns a pair of nonnegative polynomial p = mᵀQm and the coefficient
* matrix Q, where m is @p monomial_basis. Adds Q as decision variables to the
* program. Depending on the type of the polynomial, we will impose different
* constraint on Q.
* if type = kSos, we impose Q being positive semidefinite.
* if type = kSdsos, we impose Q being scaled diagonally dominant.
* if type = kDsos, we impose Q being positive diagonally dominant.
* @param monomial_basis The monomial basis.
* @param type The type of the nonnegative polynomial.
* @return (p, Q) The polynomial p and the coefficient matrix Q. Q has been
* added as decision variables to the program.
*/
std::pair<symbolic::Polynomial, MatrixXDecisionVariable>
NewNonnegativePolynomial(
const Eigen::Ref<const VectorX<symbolic::Monomial>>& monomial_basis,
NonnegativePolynomial type);
/**
* Returns a pair of nonnegative polynomial p = mᵀQm and the coefficient
* matrix Q, where m is the monomial basis, containing all monomials of @p
* indeterminates of total order up to @p degree / 2, hence the polynomial p
* contains all the monomials of total order up to @p degree, as p is
* quadratic in m. Adds Q as decision variables to the program.
* Depending on the type of the polynomial, we will impose different
* constraint on Q.
* if type = kSos, we impose Q being positive semidefinite.
* if type = kSdsos, we impose Q being scaled diagonally dominant.
* if type = kDsos, we impose Q being positive diagonally dominant.
* @param indeterminates All the indeterminates in the polynomial p.
* @param degree The polynomial p will contain all the monomials up to order
* @p degree.
* @param type The type of the nonnegative polynomial.
* @return (p, Q) The polynomial p and the coefficient matrix Q. Q has been
* added as decision variables to the program.
* @pre @p degree is a positive even number.
*/
std::pair<symbolic::Polynomial, MatrixXDecisionVariable>
NewNonnegativePolynomial(const symbolic::Variables& indeterminates,
int degree, NonnegativePolynomial type);
/** Returns a pair of a SOS polynomial p = mᵀQm and the coefficient matrix Q,
* where m is the @p monomial basis.
* For example, `NewSosPolynomial(Vector2<Monomial>{x,y})` returns a
* polynomial
* p = Q₍₀,₀₎x² + 2Q₍₁,₀₎xy + Q₍₁,₁₎y²
* and Q.
* @note Q is a symmetric monomial_basis.rows() x monomial_basis.rows()
* matrix.
*/
std::pair<symbolic::Polynomial, MatrixXDecisionVariable> NewSosPolynomial(
const Eigen::Ref<const VectorX<symbolic::Monomial>>& monomial_basis);
/** Returns a pair of a SOS polynomial p = m(x)ᵀQm(x) of degree @p degree
* and the coefficient matrix Q that should be PSD, where m(x) is the
* result of calling `MonomialBasis(indeterminates, degree/2)`. For example,
* `NewSosPolynomial({x}, 4)` returns a pair of a polynomial
* p = Q₍₀,₀₎x⁴ + 2Q₍₁,₀₎ x³ + (2Q₍₂,₀₎ + Q₍₁,₁₎)x² + 2Q₍₂,₁₎x + Q₍₂,₂₎
* and Q.
*
* @throws std::runtime_error if @p degree is not a positive even integer.
* @see MonomialBasis.
*/
std::pair<symbolic::Polynomial, MatrixXDecisionVariable> NewSosPolynomial(
const symbolic::Variables& indeterminates, int degree);
/**
* Adds indeterminates, appending them to an internal vector of any
* existing indeterminates.
* @tparam rows The number of rows in the new indeterminates.
* @tparam cols The number of columns in the new indeterminates.
* @param names A vector of strings containing the name for each variable.
* @return The MatrixIndeterminate of size rows x cols, containing the
* new vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* std::array<std::string, 6> names = {"x1", "x2", "x3", "x4", "x5", "x6"};
* auto x = prog.NewIndeterminates<2, 3>(names);
* @endcode
* This adds a 2 x 3 matrix indeterminates into the program.
*
* The name of the indeterminates is only used for the user in order to ease
* readability.
*
* @exclude_from_pydrake_mkdoc{Overloads that require explicit template
* arguments (rows, cols) are not bound in pydrake.}
*/
template <int rows, int cols>
MatrixIndeterminate<rows, cols> NewIndeterminates(
const std::array<std::string, rows * cols>& names) {
MatrixIndeterminate<rows, cols> indeterminates_matrix;
NewIndeterminates_impl(names, indeterminates_matrix);
return indeterminates_matrix;
}
/**
* Adds indeterminates, appending them to an internal vector of any
* existing indeterminates.
* @tparam rows The number of rows in the new indeterminates.
* @tparam cols The number of columns in the new indeterminates.
* @param names A vector of strings containing the name for each variable.
* @return The MatrixIndeterminate of size rows x cols, containing the
* new vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* std::array<std::string, 2> names = {"x1", "x2"};
* auto x = prog.NewIndeterminates<2>(names);
* @endcode
* This adds a 2 vector indeterminates into the program.
*
* The name of the indeterminates is only used for the user in order to ease
* readability.
*
* @exclude_from_pydrake_mkdoc{Overloads that require explicit template
* arguments (rows) are not bound in pydrake.}
*/
template <int rows>
VectorIndeterminate<rows> NewIndeterminates(
const std::array<std::string, rows>& names) {
return NewIndeterminates<rows, 1>(names);
}
/**
* Adds indeterminates, appending them to an internal vector of any
* existing indeterminates.
* @tparam rows The number of rows in the new indeterminates.
* @tparam cols The number of columns in the new indeterminates.
* @param names A vector of strings containing the name for each variable.
* @return The MatrixIndeterminate of size rows x cols, containing the
* new vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* auto x = prog.NewIndeterminates<2, 3>("X");
* @endcode
* This adds a 2 x 3 matrix indeterminates into the program.
*
* The name of the indeterminates is only used for the user in order to ease
* readability.
*
* @exclude_from_pydrake_mkdoc{Overloads that require explicit template
* arguments (rows, cols) are not bound in pydrake.}
*/
template <int rows, int cols>
MatrixIndeterminate<rows, cols> NewIndeterminates(
const std::string& name = "X") {
std::array<std::string, rows * cols> names;
for (int j = 0; j < cols; ++j) {
for (int i = 0; i < rows; ++i) {
names[j * rows + i] =
name + "(" + std::to_string(i) + "," + std::to_string(j) + ")";
}
}
return NewIndeterminates<rows, cols>(names);
}
/**
* Adds indeterminates to the program.
* The name for all newly added indeterminates are set to @p name. The default
* name is "x"
* @see NewIndeterminates(const std::array<std::string, rows>& names)
*
* @exclude_from_pydrake_mkdoc{Overloads that require explicit template
* arguments (rows) are not bound in pydrake.}
*/
template <int rows>
VectorIndeterminate<rows> NewIndeterminates(const std::string& name = "x") {
std::array<std::string, rows> names;
int offset = (name.compare("x") == 0) ? num_vars() : 0;
for (int i = 0; i < rows; ++i) {
names[i] = name + "(" + std::to_string(offset + i) + ")";
}
return NewIndeterminates<rows>(names);
}
/**
* Adds indeterminates to this MathematicalProgram.
* @see NewIndeterminates(int rows, int cols, const
* std::vector<std::string>& names);
*
* @exclude_from_pydrake_mkdoc{Not bound in pydrake.}
*/
VectorXIndeterminate NewIndeterminates(int rows,
const std::vector<std::string>& names);
/**
* Adds indeterminates to this MathematicalProgram, with default name
* "x".
* @see NewIndeterminates(int rows, int cols, const
* std::vector<std::string>& names);
*/
VectorXIndeterminate NewIndeterminates(int rows,
const std::string& name = "x");
/**
* Adds indeterminates, appending them to an internal vector of any
* existing vars.
* @param rows The number of rows in the new indeterminates.
* @param cols The number of columns in the new indeterminates.
* @param names A vector of strings containing the name for each variable.
* @return The MatrixIndeterminate of size rows x cols, containing the
* new vars (not all the vars stored).
*
* Example:
* @code{.cc}
* MathematicalProgram prog;
* auto x = prog.NewIndeterminates(2, 3, {"x1", "x2", "x3", "x4",
* "x5", "x6"});
* @endcode
* This adds a 2 x 3 matrix indeterminates into the program.
*
* The name of the variable is only used for the user in order to ease
* readability.
*
* @exclude_from_pydrake_mkdoc{Not bound in pydrake.}
*/
MatrixXIndeterminate NewIndeterminates(int rows, int cols,
const std::vector<std::string>& names);
/**
* Adds indeterminates to this MathematicalProgram, with default name
* "X". The new variables are returned and viewed as a matrix, with size
* @p rows x @p cols.
* @see NewIndeterminates(int rows, int cols, const
* std::vector<std::string>& names);
*/
MatrixXIndeterminate NewIndeterminates(int rows, int cols,
const std::string& name = "X");
/** Adds indeterminates.
* This method appends some indeterminates to the end of the program's old
* indeterminates.
* @param new_indeterminates The indeterminates to be appended to the
* program's old indeterminates.
* @pre `new_indeterminates` should not intersect with the program's old
* indeterminates or decision variables.
* @pre Each entry in new_indeterminates should not be dummy.
* @pre Each entry in new_indeterminates should be of CONTINUOUS type.
*/
void AddIndeterminates(
const Eigen::Ref<const VectorXIndeterminate>& new_indeterminates);
/**
* Adds a callback method to visualize intermediate results of the
* optimization.
*
* @note Just like other costs/constraints, not all solvers support callbacks.
* Adding a callback here will force MathematicalProgram::Solve to select a
* solver that support callbacks. For instance, adding a visualization
* callback to a quadratic programming problem may result in using a nonlinear
* programming solver as the default solver.
*
* @param callback a std::function that accepts an Eigen::Vector of doubles
* representing the bound decision variables.
* @param vars the decision variables that should be passed to the callback.
*/
Binding<VisualizationCallback> AddVisualizationCallback(
const VisualizationCallback::CallbackFunction& callback,
const Eigen::Ref<const VectorXDecisionVariable>& vars);
/**
* Adds a callback method to visualize intermediate results of the
* optimization.
*
* @note Just like other costs/constraints, not all solvers support callbacks.
* Adding a callback here will force MathematicalProgram::Solve to select a
* solver that support callbacks. For instance, adding a visualization
* callback to a quadratic programming problem may result in using a nonlinear
* programming solver as the default solver.
*
* @param callback a std::function that accepts an Eigen::Vector of doubles
* representing the for the bound decision variables.
* @param vars the decision variables that should be passed to the callback.
*
* @exclude_from_pydrake_mkdoc{Not bound in pydrake.}
*/
Binding<VisualizationCallback> AddVisualizationCallback(
const VisualizationCallback::CallbackFunction& callback,
const VariableRefList& vars) {
return AddVisualizationCallback(callback,
ConcatenateVariableRefList((vars)));
}
/**
* Adds a generic cost to the optimization program.
*/
Binding<Cost> AddCost(const Binding<Cost>& binding);
/**
* Adds a cost type to the optimization program.
* @param obj The added objective.
* @param vars The decision variables on which the cost depend.
*/
template <typename C>
auto AddCost(const std::shared_ptr<C>& obj,
const Eigen::Ref<const VectorXDecisionVariable>& vars) {
// Redirect to the appropriate type
// Use auto to enable the overloading method to upcast if needed
return AddCost(internal::CreateBinding(obj, vars));
}
/**
* Adds a generic cost to the optimization program.
* @param obj The added objective.
* @param vars The decision variables on which the cost depend.
*/
template <typename C>
auto AddCost(const std::shared_ptr<C>& obj, const VariableRefList& vars) {
return AddCost(obj, ConcatenateVariableRefList(vars));
}
/**
* Convert an input of type @p F to a FunctionCost object.
* @tparam F This class should have functions numInputs(), numOutputs and
* eval(x, y).
* @see drake::solvers::detail::FunctionTraits.
*/
template <typename F>
static std::shared_ptr<Cost> MakeCost(F&& f) {
return MakeFunctionCost(f);
}
/**
* Adds a cost to the optimization program on a list of variables.
* @tparam F it should define functions numInputs, numOutputs and eval. Check
* drake::solvers::detail::FunctionTraits for more detail.
*/
template <typename F>
typename std::enable_if<detail::is_cost_functor_candidate<F>::value,
Binding<Cost>>::type
AddCost(F&& f, const VariableRefList& vars) {
return AddCost(f, ConcatenateVariableRefList(vars));
}
/**
* Adds a cost to the optimization program on an Eigen::Vector containing
* decision variables.
* @tparam F Type that defines functions numInputs, numOutputs and eval.
* @see drake::solvers::detail::FunctionTraits.
*/
template <typename F>
typename std::enable_if<detail::is_cost_functor_candidate<F>::value,
Binding<Cost>>::type
AddCost(F&& f, const Eigen::Ref<const VectorXDecisionVariable>& vars) {
auto c = MakeFunctionCost(std::forward<F>(f));
return AddCost(c, vars);
}
/**
* Statically assert if a user inadvertently passes a
* binding-compatible Constraint.
* @tparam F The type to check.
*/
template <typename F, typename Vars>
typename std::enable_if<detail::assert_if_is_constraint<F>::value,
Binding<Cost>>::type
AddCost(F&&, Vars&&) {
throw std::runtime_error("This will assert at compile-time.");
}
/**
* Adds a cost term of the form c'*x.
* Applied to a subset of the variables and pushes onto
* the linear cost data structure.
*/
Binding<LinearCost> AddCost(const Binding<LinearCost>& binding);
/**
* Adds a linear cost term of the form a'*x + b.
* @param e A linear symbolic expression.
* @pre e is a linear expression a'*x + b, where each entry of x is a decision
* variable in the mathematical program.
* @return The newly added linear constraint, together with the bound
* variables.
*/
Binding<LinearCost> AddLinearCost(const symbolic::Expression& e);
/**
* Adds a linear cost term of the form a'*x + b.
* Applied to a subset of the variables and pushes onto
* the linear cost data structure.
*/
Binding<LinearCost> AddLinearCost(const Eigen::Ref<const Eigen::VectorXd>& a,
double b, const VariableRefList& vars) {
return AddLinearCost(a, b, ConcatenateVariableRefList((vars)));
}
/**
* Adds a linear cost term of the form a'*x + b.
* Applied to a subset of the variables and pushes onto
* the linear cost data structure.
*/
Binding<LinearCost> AddLinearCost(
const Eigen::Ref<const Eigen::VectorXd>& a, double b,
const Eigen::Ref<const VectorXDecisionVariable>& vars);
/**
* Adds a linear cost term of the form a'*x.
* Applied to a subset of the variables and pushes onto
* the linear cost data structure.
*/
template <typename VarType>
Binding<LinearCost> AddLinearCost(const Eigen::Ref<const Eigen::VectorXd>& a,
const VarType& vars) {
const double b = 0.;
return AddLinearCost(a, b, vars);
}
/**
* Adds a cost term of the form 0.5*x'*Q*x + b'x.
* Applied to subset of the variables and pushes onto
* the quadratic cost data structure.
*/
Binding<QuadraticCost> AddCost(const Binding<QuadraticCost>& binding);
/**
* Add a quadratic cost term of the form 0.5*x'*Q*x + b'*x + c.
* Notice that in the optimization program, the constant term `c` in the cost
* is ignored.
* @param e A quadratic symbolic expression.