Drake
MathematicalProgram Class Reference

Detailed Description

MathematicalProgram stores the decision variables, the constraints and costs of an optimization problem.

The user can solve the problem by calling solvers::Solve() function, and obtain the results of the optimization.

#include <drake/solvers/mathematical_program.h>

Public Types

enum  NonnegativePolynomial { kSos, kSdsos, kDsos }
 Types of non-negative polynomial that can be found through conic optimization. More...
 
using VarType = symbolic::Variable::Type
 

Public Member Functions

 MathematicalProgram ()
 
virtual ~MathematicalProgram ()
 
std::unique_ptr< MathematicalProgramClone () const
 Clones an optimization program. More...
 
VectorXDecisionVariable NewContinuousVariables (int rows, const std::string &name="x")
 Adds continuous variables, appending them to an internal vector of any existing vars. More...
 
template<int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
MatrixDecisionVariable< Rows, Cols > NewContinuousVariables (int rows, int cols, const std::string &name="X")
 Adds continuous variables, appending them to an internal vector of any existing vars. More...
 
template<int Rows, int Cols = 1>
MatrixDecisionVariable< Rows, Cols > NewContinuousVariables (const std::string &name="X")
 Adds continuous variables, appending them to an internal vector of any existing vars. More...
 
template<int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
MatrixDecisionVariable< Rows, Cols > NewBinaryVariables (int rows, int cols, const std::string &name)
 Adds binary variables, appending them to an internal vector of any existing vars. More...
 
template<int Rows, int Cols = 1>
MatrixDecisionVariable< Rows, Cols > NewBinaryVariables (const std::string &name="b")
 Adds a matrix of binary variables into the optimization program. More...
 
VectorXDecisionVariable NewBinaryVariables (int rows, const std::string &name="b")
 Adds binary variables to this MathematicalProgram. More...
 
MatrixXDecisionVariable NewSymmetricContinuousVariables (int rows, const std::string &name="Symmetric")
 Adds a runtime sized symmetric matrix as decision variables to this MathematicalProgram. More...
 
template<int rows>
MatrixDecisionVariable< rows, rowsNewSymmetricContinuousVariables (const std::string &name="Symmetric")
 Adds a static sized symmetric matrix as decision variables to this MathematicalProgram. More...
 
void AddDecisionVariables (const Eigen::Ref< const VectorXDecisionVariable > &decision_variables)
 Appends new variables to the end of the existing variables. More...
 
symbolic::Polynomial NewFreePolynomial (const symbolic::Variables &indeterminates, int degree, const std::string &coeff_name="a")
 Returns a free polynomial in a monomial basis over indeterminates of a given degree. More...
 
std::pair< symbolic::Polynomial, MatrixXDecisionVariableNewNonnegativePolynomial (const Eigen::Ref< const VectorX< symbolic::Monomial >> &monomial_basis, NonnegativePolynomial type)
 Returns a pair of nonnegative polynomial p = mᵀQm and the Grammian matrix Q, where m is monomial_basis. More...
 
symbolic::Polynomial NewNonnegativePolynomial (const Eigen::Ref< const MatrixX< symbolic::Variable >> &grammian, const Eigen::Ref< const VectorX< symbolic::Monomial >> &monomial_basis, NonnegativePolynomial type)
 Overloads NewNonnegativePolynomial(), except the Grammian matrix Q is an input instead of an output. More...
 
std::pair< symbolic::Polynomial, MatrixXDecisionVariableNewNonnegativePolynomial (const symbolic::Variables &indeterminates, int degree, NonnegativePolynomial type)
 Overloads NewNonnegativePolynomial(). More...
 
std::pair< symbolic::Polynomial, MatrixXDecisionVariableNewSosPolynomial (const Eigen::Ref< const VectorX< symbolic::Monomial >> &monomial_basis)
 Returns a pair of a SOS polynomial p = mᵀQm and the Grammian matrix Q, where m is the monomial basis. More...
 
std::pair< symbolic::Polynomial, MatrixXDecisionVariableNewSosPolynomial (const symbolic::Variables &indeterminates, int degree)
 Returns a pair of a SOS polynomial p = m(x)ᵀQm(x) of degree degree and the Grammian matrix Q that should be PSD, where m(x) is the result of calling MonomialBasis(indeterminates, degree/2). More...
 
template<int rows, int cols>
MatrixIndeterminate< rows, colsNewIndeterminates (const std::array< std::string, rows *cols > &names)
 Adds indeterminates, appending them to an internal vector of any existing indeterminates. More...
 
template<int rows>
VectorIndeterminate< rowsNewIndeterminates (const std::array< std::string, rows > &names)
 Adds indeterminates, appending them to an internal vector of any existing indeterminates. More...
 
template<int rows, int cols>
MatrixIndeterminate< rows, colsNewIndeterminates (const std::string &name="X")
 Adds indeterminates, appending them to an internal vector of any existing indeterminates. More...
 
template<int rows>
VectorIndeterminate< rowsNewIndeterminates (const std::string &name="x")
 Adds indeterminates to the program. More...
 
VectorXIndeterminate NewIndeterminates (int rows, const std::vector< std::string > &names)
 Adds indeterminates to this MathematicalProgram. More...
 
VectorXIndeterminate NewIndeterminates (int rows, const std::string &name="x")
 Adds indeterminates to this MathematicalProgram, with default name "x". More...
 
MatrixXIndeterminate NewIndeterminates (int rows, int cols, const std::vector< std::string > &names)
 Adds indeterminates, appending them to an internal vector of any existing vars. More...
 
MatrixXIndeterminate NewIndeterminates (int rows, int cols, const std::string &name="X")
 Adds indeterminates to this MathematicalProgram, with default name "X". More...
 
void AddIndeterminates (const Eigen::Ref< const VectorXIndeterminate > &new_indeterminates)
 Adds indeterminates. More...
 
Binding< VisualizationCallbackAddVisualizationCallback (const VisualizationCallback::CallbackFunction &callback, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a callback method to visualize intermediate results of the optimization. More...
 
Binding< VisualizationCallbackAddVisualizationCallback (const VisualizationCallback::CallbackFunction &callback, const VariableRefList &vars)
 Adds a callback method to visualize intermediate results of the optimization. More...
 
Binding< CostAddCost (const Binding< Cost > &binding)
 Adds a generic cost to the optimization program. More...
 
template<typename C >
auto AddCost (const std::shared_ptr< C > &obj, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a cost type to the optimization program. More...
 
template<typename C >
auto AddCost (const std::shared_ptr< C > &obj, const VariableRefList &vars)
 Adds a generic cost to the optimization program. More...
 
template<typename F >
std::enable_if< internal::is_cost_functor_candidate< F >::value, Binding< Cost > >::type AddCost (F &&f, const VariableRefList &vars)
 Adds a cost to the optimization program on a list of variables. More...
 
template<typename F >
std::enable_if< internal::is_cost_functor_candidate< F >::value, Binding< Cost > >::type AddCost (F &&f, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a cost to the optimization program on an Eigen::Vector containing decision variables. More...
 
template<typename F , typename Vars >
std::enable_if< internal::assert_if_is_constraint< F >::value, Binding< Cost > >::type AddCost (F &&, Vars &&)
 Statically assert if a user inadvertently passes a binding-compatible Constraint. More...
 
Binding< LinearCostAddCost (const Binding< LinearCost > &binding)
 Adds a cost term of the form c'*x. More...
 
Binding< LinearCostAddLinearCost (const symbolic::Expression &e)
 Adds a linear cost term of the form a'*x + b. More...
 
Binding< LinearCostAddLinearCost (const Eigen::Ref< const Eigen::VectorXd > &a, double b, const VariableRefList &vars)
 Adds a linear cost term of the form a'*x + b. More...
 
Binding< LinearCostAddLinearCost (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 + b. More...
 
template<typename VarType >
Binding< LinearCostAddLinearCost (const Eigen::Ref< const Eigen::VectorXd > &a, const VarType &vars)
 Adds a linear cost term of the form a'*x. More...
 
Binding< QuadraticCostAddCost (const Binding< QuadraticCost > &binding)
 Adds a cost term of the form 0.5*x'*Q*x + b'x. More...
 
Binding< QuadraticCostAddQuadraticCost (const symbolic::Expression &e)
 Add a quadratic cost term of the form 0.5*x'*Q*x + b'*x + c. More...
 
Binding< QuadraticCostAddQuadraticErrorCost (const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::VectorXd > &x_desired, const VariableRefList &vars)
 Adds a cost term of the form (x-x_desired)'Q(x-x_desired). More...
 
Binding< QuadraticCostAddQuadraticErrorCost (const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::VectorXd > &x_desired, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a cost term of the form (x-x_desired)'Q(x-x_desired). More...
 
Binding< QuadraticCostAddL2NormCost (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const VariableRefList &vars)
 Adds a cost term of the form | Ax - b |^2. More...
 
Binding< QuadraticCostAddL2NormCost (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a cost term of the form | Ax - b |^2. More...
 
Binding< QuadraticCostAddQuadraticCost (const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::VectorXd > &b, const VariableRefList &vars)
 Adds a cost term of the form 0.5*x'*Q*x + b'x. More...
 
Binding< QuadraticCostAddQuadraticCost (const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::VectorXd > &b, double c, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a cost term of the form 0.5*x'*Q*x + b'x + c Applied to subset of the variables. More...
 
Binding< QuadraticCostAddQuadraticCost (const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::VectorXd > &b, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a cost term of the form 0.5*x'*Q*x + b'x Applied to subset of the variables. More...
 
Binding< PolynomialCostAddPolynomialCost (const symbolic::Expression &e)
 Adds a cost term in the polynomial form. More...
 
Binding< CostAddCost (const symbolic::Expression &e)
 Adds a cost in the symbolic form. More...
 
void AddMaximizeLogDeterminantSymmetricMatrixCost (const Eigen::Ref< const MatrixX< symbolic::Expression >> &X)
 Adds the cost to maximize the log determinant of symmetric matrix X. More...
 
Binding< ConstraintAddConstraint (const Binding< Constraint > &binding)
 Adds a generic constraint to the program. More...
 
Binding< ConstraintAddConstraint (const symbolic::Expression &e, double lb, double ub)
 Adds one row of constraint lb <= e <= ub where e is a symbolic expression. More...
 
Binding< ConstraintAddConstraint (const Eigen::Ref< const VectorX< symbolic::Expression >> &v, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
 
Binding< ConstraintAddConstraint (const symbolic::Formula &f)
 Add a constraint represented by a symbolic formula to the program. More...
 
template<typename Derived >
std::enable_if< is_eigen_scalar_same< Derived, symbolic::Formula >::value, Binding< Constraint > >::type AddConstraint (const Eigen::ArrayBase< Derived > &formulas)
 
template<typename C >
auto AddConstraint (std::shared_ptr< C > con, const VariableRefList &vars)
 Adds a generic constraint to the program. More...
 
template<typename C >
auto AddConstraint (std::shared_ptr< C > con, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a generic constraint to the program. More...
 
Binding< LinearConstraintAddConstraint (const Binding< LinearConstraint > &binding)
 Adds linear constraints referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LinearConstraintAddLinearConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, const VariableRefList &vars)
 Adds linear constraints referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LinearConstraintAddLinearConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds linear constraints referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LinearConstraintAddLinearConstraint (const Eigen::Ref< const Eigen::RowVectorXd > &a, double lb, double ub, const VariableRefList &vars)
 Adds one row of linear constraint referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LinearConstraintAddLinearConstraint (const Eigen::Ref< const Eigen::RowVectorXd > &a, double lb, double ub, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds one row of linear constraint referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LinearConstraintAddLinearConstraint (const symbolic::Expression &e, double lb, double ub)
 Adds one row of linear constraint lb <= e <= ub where e is a symbolic expression. More...
 
Binding< LinearConstraintAddLinearConstraint (const Eigen::Ref< const VectorX< symbolic::Expression >> &v, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
 Adds linear constraints represented by symbolic expressions to the program. More...
 
Binding< LinearConstraintAddLinearConstraint (const symbolic::Formula &f)
 Add a linear constraint represented by a symbolic formula to the program. More...
 
template<typename Derived >
std::enable_if< is_eigen_scalar_same< Derived, symbolic::Formula >::value, Binding< LinearConstraint > >::type AddLinearConstraint (const Eigen::ArrayBase< Derived > &formulas)
 Add a linear constraint represented by an Eigen::Array<symbolic::Formula> to the program. More...
 
Binding< LinearEqualityConstraintAddConstraint (const Binding< LinearEqualityConstraint > &binding)
 Adds linear equality constraints referencing potentially a subset of the decision variables. More...
 
Binding< LinearEqualityConstraintAddLinearEqualityConstraint (const symbolic::Expression &e, double b)
 Adds one row of linear constraint e = b where e is a symbolic expression. More...
 
Binding< LinearEqualityConstraintAddLinearEqualityConstraint (const symbolic::Formula &f)
 Adds a linear equality constraint represented by a symbolic formula to the program. More...
 
template<typename DerivedV , typename DerivedB >
std::enable_if< is_eigen_vector_expression_double_pair< DerivedV, DerivedB >::value, Binding< LinearEqualityConstraint > >::type AddLinearEqualityConstraint (const Eigen::MatrixBase< DerivedV > &v, const Eigen::MatrixBase< DerivedB > &b)
 Adds linear equality constraints \( v = b \), where v(i) is a symbolic linear expression. More...
 
template<typename DerivedV , typename DerivedB >
std::enable_if< is_eigen_nonvector_expression_double_pair< DerivedV, DerivedB >::value, Binding< LinearEqualityConstraint > >::type AddLinearEqualityConstraint (const Eigen::MatrixBase< DerivedV > &V, const Eigen::MatrixBase< DerivedB > &B, bool lower_triangle=false)
 Adds a linear equality constraint for a matrix of linear expression V, such that V(i, j) = B(i, j). More...
 
Binding< LinearEqualityConstraintAddLinearEqualityConstraint (const Eigen::Ref< const Eigen::MatrixXd > &Aeq, const Eigen::Ref< const Eigen::VectorXd > &beq, const VariableRefList &vars)
 AddLinearEqualityConstraint. More...
 
Binding< LinearEqualityConstraintAddLinearEqualityConstraint (const Eigen::Ref< const Eigen::MatrixXd > &Aeq, const Eigen::Ref< const Eigen::VectorXd > &beq, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 AddLinearEqualityConstraint. More...
 
Binding< LinearEqualityConstraintAddLinearEqualityConstraint (const Eigen::Ref< const Eigen::RowVectorXd > &a, double beq, const VariableRefList &vars)
 Adds one row of linear equality constraint referencing potentially a subset of decision variables. More...
 
Binding< LinearEqualityConstraintAddLinearEqualityConstraint (const Eigen::Ref< const Eigen::RowVectorXd > &a, double beq, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds one row of linear equality constraint referencing potentially a subset of decision variables. More...
 
Binding< BoundingBoxConstraintAddConstraint (const Binding< BoundingBoxConstraint > &binding)
 Adds bounding box constraints referencing potentially a subest of the decision variables. More...
 
Binding< BoundingBoxConstraintAddBoundingBoxConstraint (const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, const VariableRefList &vars)
 AddBoundingBoxConstraint. More...
 
Binding< BoundingBoxConstraintAddBoundingBoxConstraint (const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds bounding box constraints referencing potentially a subset of the decision variables. More...
 
Binding< BoundingBoxConstraintAddBoundingBoxConstraint (double lb, double ub, const symbolic::Variable &var)
 Adds bounds for a single variable. More...
 
Binding< BoundingBoxConstraintAddBoundingBoxConstraint (double lb, double ub, const VariableRefList &vars)
 Adds the same scalar lower and upper bound to every variable in the list. More...
 
template<typename Derived >
std::enable_if< std::is_same< typename Derived::Scalar, symbolic::Variable >::value &&Derived::ColsAtCompileTime==1, Binding< BoundingBoxConstraint > >::type AddBoundingBoxConstraint (double lb, double ub, const Eigen::MatrixBase< Derived > &vars)
 Adds the same scalar lower and upper bound to every variable in vars. More...
 
template<typename Derived >
std::enable_if< std::is_same< typename Derived::Scalar, symbolic::Variable >::value &&Derived::ColsAtCompileTime !=1, Binding< BoundingBoxConstraint > >::type AddBoundingBoxConstraint (double lb, double ub, const Eigen::MatrixBase< Derived > &vars)
 Adds the same scalar lower and upper bound to every variable in vars. More...
 
Binding< LorentzConeConstraintAddConstraint (const Binding< LorentzConeConstraint > &binding)
 Adds Lorentz cone constraint referencing potentially a subset of the decision variables. More...
 
Binding< LorentzConeConstraintAddLorentzConeConstraint (const Eigen::Ref< const VectorX< symbolic::Expression >> &v)
 Adds Lorentz cone constraint referencing potentially a subset of the decision variables. More...
 
Binding< LorentzConeConstraintAddLorentzConeConstraint (const symbolic::Expression &linear_expression, const symbolic::Expression &quadratic_expression, double tol=0)
 Adds Lorentz cone constraint on the linear expression v1 and quadratic expression v2, such that v1 >= sqrt(v2) More...
 
Binding< LorentzConeConstraintAddLorentzConeConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const VariableRefList &vars)
 Adds Lorentz cone constraint referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LorentzConeConstraintAddLorentzConeConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds Lorentz cone constraint referencing potentially a subset of the decision variables (defined in the vars parameter). More...
 
Binding< LorentzConeConstraintAddLorentzConeConstraint (const VariableRefList &vars)
 Imposes that a vector \( x\in\mathbb{R}^m \) lies in Lorentz cone. More...
 
template<int rows>
Binding< LorentzConeConstraintAddLorentzConeConstraint (const Eigen::MatrixBase< VectorDecisionVariable< rows >> &vars)
 Imposes that a vector \( x\in\mathbb{R}^m \) lies in Lorentz cone. More...
 
Binding< RotatedLorentzConeConstraintAddConstraint (const Binding< RotatedLorentzConeConstraint > &binding)
 Adds a rotated Lorentz cone constraint referencing potentially a subset of decision variables. More...
 
Binding< RotatedLorentzConeConstraintAddRotatedLorentzConeConstraint (const symbolic::Expression &linear_expression1, const symbolic::Expression &linear_expression2, const symbolic::Expression &quadratic_expression, double tol=0)
 Adds rotated Lorentz cone constraint on the linear expression v1, v2 and quadratic expression u, such that v1 * v2 >= u, v1 >= 0, v2 >= 0. More...
 
Binding< RotatedLorentzConeConstraintAddRotatedLorentzConeConstraint (const Eigen::Ref< const VectorX< symbolic::Expression >> &v)
 Adds a constraint that a symbolic expression. More...
 
Binding< RotatedLorentzConeConstraintAddRotatedLorentzConeConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const VariableRefList &vars)
 Adds a rotated Lorentz cone constraint referencing potentially a subset of decision variables, The linear expression \( z=Ax+b \) is in rotated Lorentz cone. More...
 
Binding< RotatedLorentzConeConstraintAddRotatedLorentzConeConstraint (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a rotated Lorentz cone constraint referencing potentially a subset of decision variables, The linear expression \( z=Ax+b \) is in rotated Lorentz cone. More...
 
Binding< RotatedLorentzConeConstraintAddRotatedLorentzConeConstraint (const VariableRefList &vars)
 Impose that a vector \( x\in\mathbb{R}^m \) is in rotated Lorentz cone. More...
 
template<int rows>
Binding< RotatedLorentzConeConstraintAddRotatedLorentzConeConstraint (const Eigen::MatrixBase< VectorDecisionVariable< rows >> &vars)
 Impose that a vector \( x\in\mathbb{R}^m \) is in rotated Lorentz cone. More...
 
Binding< LinearComplementarityConstraintAddConstraint (const Binding< LinearComplementarityConstraint > &binding)
 Adds a linear complementarity constraints referencing a subset of the decision variables. More...
 
Binding< LinearComplementarityConstraintAddLinearComplementarityConstraint (const Eigen::Ref< const Eigen::MatrixXd > &M, const Eigen::Ref< const Eigen::VectorXd > &q, const VariableRefList &vars)
 Adds a linear complementarity constraints referencing a subset of the decision variables. More...
 
Binding< LinearComplementarityConstraintAddLinearComplementarityConstraint (const Eigen::Ref< const Eigen::MatrixXd > &M, const Eigen::Ref< const Eigen::VectorXd > &q, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a linear complementarity constraints referencing a subset of the decision variables. More...
 
Binding< ConstraintAddPolynomialConstraint (const VectorXPoly &polynomials, const std::vector< Polynomiald::VarType > &poly_vars, const Eigen::VectorXd &lb, const Eigen::VectorXd &ub, const VariableRefList &vars)
 Adds a polynomial constraint to the program referencing a subset of the decision variables (defined in the vars parameter). More...
 
Binding< ConstraintAddPolynomialConstraint (const VectorXPoly &polynomials, const std::vector< Polynomiald::VarType > &poly_vars, const Eigen::VectorXd &lb, const Eigen::VectorXd &ub, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a polynomial constraint to the program referencing a subset of the decision variables (defined in the vars parameter). More...
 
Binding< PositiveSemidefiniteConstraintAddConstraint (const Binding< PositiveSemidefiniteConstraint > &binding)
 Adds a positive semidefinite constraint on a symmetric matrix. More...
 
Binding< PositiveSemidefiniteConstraintAddConstraint (std::shared_ptr< PositiveSemidefiniteConstraint > con, const Eigen::Ref< const MatrixXDecisionVariable > &symmetric_matrix_var)
 Adds a positive semidefinite constraint on a symmetric matrix. More...
 
Binding< PositiveSemidefiniteConstraintAddPositiveSemidefiniteConstraint (const Eigen::Ref< const MatrixXDecisionVariable > &symmetric_matrix_var)
 Adds a positive semidefinite constraint on a symmetric matrix. More...
 
template<typename Derived >
std::enable_if< std::is_same< typename Derived::Scalar, symbolic::Expression >::value, Binding< PositiveSemidefiniteConstraint > >::type AddPositiveSemidefiniteConstraint (const Eigen::MatrixBase< Derived > &e)
 Adds a positive semidefinite constraint on a symmetric matrix of symbolic expressions e. More...
 
Binding< LinearMatrixInequalityConstraintAddConstraint (const Binding< LinearMatrixInequalityConstraint > &binding)
 Adds a linear matrix inequality constraint to the program. More...
 
Binding< LinearMatrixInequalityConstraintAddLinearMatrixInequalityConstraint (const std::vector< Eigen::Ref< const Eigen::MatrixXd >> &F, const VariableRefList &vars)
 Adds a linear matrix inequality constraint to the program. More...
 
Binding< LinearMatrixInequalityConstraintAddLinearMatrixInequalityConstraint (const std::vector< Eigen::Ref< const Eigen::MatrixXd >> &F, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds a linear matrix inequality constraint to the program. More...
 
MatrixX< symbolic::ExpressionAddPositiveDiagonallyDominantMatrixConstraint (const Eigen::Ref< const MatrixX< symbolic::Expression >> &X)
 Adds the constraint that a symmetric matrix is diagonally dominant with non-negative diagonal entries. More...
 
MatrixXDecisionVariable AddSosConstraint (const symbolic::Polynomial &p, const Eigen::Ref< const VectorX< symbolic::Monomial >> &monomial_basis)
 Adds constraints that a given polynomial p is a sums-of-squares (SOS), that is, p can be decomposed into mᵀQm, where m is the monomial_basis. More...
 
std::pair< MatrixXDecisionVariable, VectorX< symbolic::Monomial > > AddSosConstraint (const symbolic::Polynomial &p)
 Adds constraints that a given polynomial p is a sums-of-squares (SOS), that is, p can be decomposed into mᵀQm, where m is a monomial basis selected from the sparsity of p. More...
 
MatrixXDecisionVariable AddSosConstraint (const symbolic::Expression &e, const Eigen::Ref< const VectorX< symbolic::Monomial >> &monomial_basis)
 Adds constraints that a given symbolic expression e is a sums-of-squares (SOS), that is, p can be decomposed into mᵀQm, where m is the monomial_basis. More...
 
std::pair< MatrixXDecisionVariable, VectorX< symbolic::Monomial > > AddSosConstraint (const symbolic::Expression &e)
 Adds constraints that a given symbolic expression e is a sums-of-squares (SOS), that is, e can be decomposed into mᵀQm. More...
 
void AddEqualityConstraintBetweenPolynomials (const symbolic::Polynomial &p1, const symbolic::Polynomial &p2)
 Constraining that two polynomials are the same (i.e., they have the same coefficients for each monomial). More...
 
Binding< ExponentialConeConstraintAddConstraint (const Binding< ExponentialConeConstraint > &binding)
 Adds the exponential cone constraint that z = binding.evaluator()->A() * binding.variables() + binding.evaluator()->b() should be in the exponential cone. More...
 
Binding< ExponentialConeConstraintAddExponentialConeConstraint (const Eigen::Ref< const Eigen::SparseMatrix< double >> &A, const Eigen::Ref< const Eigen::Vector3d > &b, const Eigen::Ref< const VectorXDecisionVariable > &vars)
 Adds an exponential cone constraint, that z = A * vars + b should be in the exponential cone. More...
 
Binding< ExponentialConeConstraintAddExponentialConeConstraint (const Eigen::Ref< const Vector3< symbolic::Expression >> &z)
 Add the constraint that z is in the exponential cone. More...
 
double GetInitialGuess (const symbolic::Variable &decision_variable) const
 Gets the initial guess for a single variable. More...
 
template<typename Derived >
std::enable_if< std::is_same< typename Derived::Scalar, symbolic::Variable >::value, Eigen::Matrix< double, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime > >::type GetInitialGuess (const Eigen::MatrixBase< Derived > &decision_variable_mat) const
 Gets the initial guess for some variables. More...
 
void SetInitialGuess (const symbolic::Variable &decision_variable, double variable_guess_value)
 Sets the initial guess for a single variable decision_variable. More...
 
template<typename DerivedA , typename DerivedB >
void SetInitialGuess (const Eigen::MatrixBase< DerivedA > &decision_variable_mat, const Eigen::MatrixBase< DerivedB > &x0)
 Sets the initial guess for the decision variables stored in decision_variable_mat to be x0. More...
 
template<typename Derived >
void SetInitialGuessForAllVariables (const Eigen::MatrixBase< Derived > &x0)
 Set the initial guess for ALL decision variables. More...
 
void SetDecisionVariableValueInVector (const symbolic::Variable &decision_variable, double decision_variable_new_value, EigenPtr< Eigen::VectorXd > values) const
 Updates the value of a single decision_variable inside the values vector to be decision_variable_new_value. More...
 
void SetDecisionVariableValueInVector (const Eigen::Ref< const MatrixXDecisionVariable > &decision_variables, const Eigen::Ref< const Eigen::MatrixXd > &decision_variables_new_values, EigenPtr< Eigen::VectorXd > values) const
 Updates the values of some decision_variables inside the values vector to be decision_variables_new_values. More...
 
void SetSolverOption (const SolverId &solver_id, const std::string &solver_option, double option_value)
 
void SetSolverOption (const SolverId &solver_id, const std::string &solver_option, int option_value)
 
void SetSolverOption (const SolverId &solver_id, const std::string &solver_option, const std::string &option_value)
 
void SetSolverOptions (const SolverOptions &solver_options)
 Overwrite the stored solver options inside MathematicalProgram with the provided solver options. More...
 
const SolverOptionssolver_options () const
 Returns the solver options stored inside MathematicalProgram. More...
 
const std::unordered_map< std::string, double > & GetSolverOptionsDouble (const SolverId &solver_id) const
 
const std::unordered_map< std::string, int > & GetSolverOptionsInt (const SolverId &solver_id) const
 
const std::unordered_map< std::string, std::string > & GetSolverOptionsStr (const SolverId &solver_id) const
 
const std::vector< Binding< VisualizationCallback > > & visualization_callbacks () const
 Getter for all callbacks. More...
 
const std::vector< Binding< Cost > > & generic_costs () const
 Getter for all generic costs. More...
 
const std::vector< Binding< Constraint > > & generic_constraints () const
 Getter for all generic constraints. More...
 
const std::vector< Binding< LinearEqualityConstraint > > & linear_equality_constraints () const
 Getter for linear equality constraints. More...
 
const std::vector< Binding< LinearCost > > & linear_costs () const
 Getter for linear costs. More...
 
const std::vector< Binding< QuadraticCost > > & quadratic_costs () const
 Getter for quadratic costs. More...
 
const std::vector< Binding< LinearConstraint > > & linear_constraints () const
 Getter for linear constraints. More...
 
const std::vector< Binding< LorentzConeConstraint > > & lorentz_cone_constraints () const
 Getter for Lorentz cone constraints. More...
 
const std::vector< Binding< RotatedLorentzConeConstraint > > & rotated_lorentz_cone_constraints () const
 Getter for rotated Lorentz cone constraints. More...
 
const std::vector< Binding< PositiveSemidefiniteConstraint > > & positive_semidefinite_constraints () const
 Getter for positive semidefinite constraints. More...
 
const std::vector< Binding< LinearMatrixInequalityConstraint > > & linear_matrix_inequality_constraints () const
 Getter for linear matrix inequality constraints. More...
 
const std::vector< Binding< ExponentialConeConstraint > > & exponential_cone_constraints () const
 Getter for exponential cone constraints. More...
 
std::vector< Binding< Cost > > GetAllCosts () const
 Getter returning all costs. More...
 
std::vector< Binding< LinearConstraint > > GetAllLinearConstraints () const
 Getter returning all linear constraints (both linear equality and inequality constraints). More...
 
std::vector< Binding< Constraint > > GetAllConstraints () const
 Getter for returning all constraints. More...
 
const std::vector< Binding< BoundingBoxConstraint > > & bounding_box_constraints () const
 Getter for all bounding box constraints. More...
 
const std::vector< Binding< LinearComplementarityConstraint > > & linear_complementarity_constraints () const
 Getter for all linear complementarity constraints. More...
 
int num_vars () const
 Getter for number of variables in the optimization program. More...
 
const Eigen::VectorXd & initial_guess () const
 Getter for the initial guess. More...
 
int FindDecisionVariableIndex (const symbolic::Variable &var) const
 Returns the index of the decision variable. More...
 
std::vector< intFindDecisionVariableIndices (const Eigen::Ref< const VectorXDecisionVariable > &vars) const
 Returns the indices of the decision variables. More...
 
int num_indeterminates () const
 Gets the number of indeterminates in the optimization program. More...
 
size_t FindIndeterminateIndex (const symbolic::Variable &var) const
 Returns the index of the indeterminate. More...
 
template<typename C , typename DerivedX >
std::enable_if< is_eigen_vector< DerivedX >::value, VectorX< typename DerivedX::Scalar > >::type EvalBinding (const Binding< C > &binding, const Eigen::MatrixBase< DerivedX > &prog_var_vals) const
 Evaluates the value of some binding, for some input value for all decision variables. More...
 
template<typename C , typename DerivedX >
std::enable_if< is_eigen_vector< DerivedX >::value, VectorX< typename DerivedX::Scalar > >::type EvalBindings (const std::vector< Binding< C >> &bindings, const Eigen::MatrixBase< DerivedX > &prog_var_vals) const
 Evaluates a set of bindings (plural version of EvalBinding). More...
 
void EvalVisualizationCallbacks (const Eigen::Ref< const Eigen::VectorXd > &prog_var_vals) const
 Evaluates all visualization callbacks registered with the MathematicalProgram. More...
 
template<typename C >
Eigen::VectorXd EvalBindingAtInitialGuess (const Binding< C > &binding) const
 Evaluates the evaluator in binding at the initial guess. More...
 
const VectorXDecisionVariabledecision_variables () const
 Getter for all decision variables in the program. More...
 
const symbolic::Variabledecision_variable (int i) const
 Getter for the decision variable with index i in the program. More...
 
const VectorXIndeterminateindeterminates () const
 Getter for all indeterminates in the program. More...
 
const symbolic::Variableindeterminate (int i) const
 Getter for the indeterminate with index i in the program. More...
 
const ProgramAttributesrequired_capabilities () const
 Getter for the required capability on the solver, given the cost/constraint/variable types in the program. More...
 
const std::unordered_map< symbolic::Variable::Id, int > & decision_variable_index () const
 Returns the mapping from a decision variable to its index in the vector, containing all the decision variables in the optimization program. More...
 
Does not allow copy, move, or assignment
 MathematicalProgram (const MathematicalProgram &)=delete
 
MathematicalProgramoperator= (const MathematicalProgram &)=delete
 
 MathematicalProgram (MathematicalProgram &&)=delete
 
MathematicalProgramoperator= (MathematicalProgram &&)=delete
 
Maximize geometric mean

Adds the cost to maximize the geometric mean of z = Ax+b, i.e. power(∏ᵢz(i), 1/n), where z ∈ ℝⁿ, z(i) >= 0. Mathematically, the cost we add is -power(∏ᵢz(i), 1/r), where r = power(2, ceil(log₂n)), namely r is the smallest power of 2 that is no smaller than the size of z. For example, if z ∈ ℝ², then the added cost is -power(z(0)*z(1), 1/2) if z ∈ ℝ³, then the added cost is -power(z(0)*z(1)*z(2), 1/4).

In order to add this cost, we need to introduce a set of second-order cone constraints. For example, to maximize power(z(0) * z(1), 1/2), we introduce the slack variable w(0), together with the second order cone constraint w(0)² ≤ z(0) * z(1), z(0) ≥ 0, z(1) ≥ 0, and we maximize w(0).

To maximize power(z(0) * z(1) * z(2), 1/ 4), we introduce the slack variable w(0), w(1), w(2), together with the second order cone constraints

w(0)² ≤ z(0) * z(1), z(0) ≥ 0, z(1) ≥ 0
w(1)² ≤ z(2), z(2) ≥ 0
w(2)² ≤ w(0) * w(1), w(0) ≥ 0, w(1) ≥ 0

and we maximize w(2).

void AddMaximizeGeometricMeanCost (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const Eigen::Ref< const VectorX< symbolic::Variable >> &x)
 An overloaded version of maximize_geometric_mean. More...
 
void AddMaximizeGeometricMeanCost (const Eigen::Ref< const VectorX< symbolic::Variable >> &x, double c=1.0)
 An overloaded version of maximize_geometric_mean. More...
 
scaled diagonally dominant matrix constraint

Adds the constraint that a symmetric matrix is scaled diagonally dominant (sdd). A matrix X is sdd if there exists a diagonal matrix D, such that the product DXD is diagonally dominant with non-negative diagonal entries, namely d(i)X(i, i) ≥ ∑ⱼ |d(j)X(i, j)| ∀ j ≠ i where d(i) = D(i, i). X being sdd is equivalent to the existence of symmetric matrices Mⁱʲ∈ ℝⁿˣⁿ, i < j, such that all entries in Mⁱʲ are 0, except Mⁱʲ(i, i), Mⁱʲ(i, j), Mⁱʲ(j, j). (Mⁱʲ(i, i), Mⁱʲ(j, j), Mⁱʲ(i, j)) is in the rotated Lorentz cone, and X = ∑ᵢⱼ Mⁱʲ.

The users can 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.

std::vector< std::vector< Matrix2< symbolic::Expression > > > AddScaledDiagonallyDominantMatrixConstraint (const Eigen::Ref< const MatrixX< symbolic::Expression >> &X)
 This is an overloaded variant of scaled diagonally dominant matrix constraint. More...
 
std::vector< std::vector< Matrix2< symbolic::Variable > > > AddScaledDiagonallyDominantMatrixConstraint (const Eigen::Ref< const MatrixX< symbolic::Variable >> &X)
 This is an overloaded variant of scaled diagonally dominant matrix constraint. More...
 

Static Public Member Functions

template<typename F >
static std::shared_ptr< CostMakeCost (F &&f)
 Convert an input of type F to a FunctionCost object. More...
 

Static Public Attributes

static constexpr double kGlobalInfeasibleCost
 The optimal cost is +∞ when the problem is globally infeasible. More...
 
static constexpr double kUnboundedCost
 The optimal cost is -∞ when the problem is unbounded. More...
 

Member Typedef Documentation

◆ VarType

Member Enumeration Documentation

◆ NonnegativePolynomial

enum NonnegativePolynomial
strong

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

Enumerator
kSos 

A sum-of-squares polynomial.

kSdsos 

A scaled-diagonally dominant sum-of-squares polynomial.

kDsos 

A diagonally dominant sum-of-squares polynomial.

Constructor & Destructor Documentation

◆ MathematicalProgram() [1/3]

◆ MathematicalProgram() [2/3]

◆ MathematicalProgram() [3/3]

◆ ~MathematicalProgram()

~MathematicalProgram ( )
virtualdefault

Member Function Documentation

◆ AddBoundingBoxConstraint() [1/6]

Binding<BoundingBoxConstraint> AddBoundingBoxConstraint ( const Eigen::Ref< const Eigen::VectorXd > &  lb,
const Eigen::Ref< const Eigen::VectorXd > &  ub,
const VariableRefList vars 
)

AddBoundingBoxConstraint.

Adds bounding box constraints referencing potentially a subset of the decision variables (defined in the vars parameter). Example

auto x = prog.NewContinuousVariables<2>("x");
auto y = prog.NewContinuousVariables<1>("y");
Eigen::Vector3d lb(0, 1, 2);
Eigen::Vector3d ub(1, 2, 3);
// Imposes the constraint
// 0 ≤ x(0) ≤ 1
// 1 ≤ x(1) ≤ 2
// 2 ≤ y ≤ 3
prog.AddBoundingBoxConstraint(lb, ub, {x, y});

◆ AddBoundingBoxConstraint() [2/6]

Binding< BoundingBoxConstraint > AddBoundingBoxConstraint ( const Eigen::Ref< const Eigen::VectorXd > &  lb,
const Eigen::Ref< const Eigen::VectorXd > &  ub,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds bounding box constraints referencing potentially a subset of the decision variables.

Parameters
lbThe lower bound.
ubThe upper bound.
varsWill imposes constraint lb(i) <= vars(i) <= ub(i).
Returns
The newly constructed BoundingBoxConstraint.

◆ AddBoundingBoxConstraint() [3/6]

Binding<BoundingBoxConstraint> AddBoundingBoxConstraint ( double  lb,
double  ub,
const symbolic::Variable var 
)

Adds bounds for a single variable.

Parameters
lbLower bound.
ubUpper bound.
varThe decision variable.

◆ AddBoundingBoxConstraint() [4/6]

Binding<BoundingBoxConstraint> AddBoundingBoxConstraint ( double  lb,
double  ub,
const VariableRefList vars 
)

Adds the same scalar lower and upper bound to every variable in the list.

Parameters
lbLower bound.
ubUpper bound.
varsThe decision variables.

◆ AddBoundingBoxConstraint() [5/6]

std::enable_if< std::is_same<typename Derived::Scalar, symbolic::Variable>::value && Derived::ColsAtCompileTime == 1, Binding<BoundingBoxConstraint> >::type AddBoundingBoxConstraint ( double  lb,
double  ub,
const Eigen::MatrixBase< Derived > &  vars 
)

Adds the same scalar lower and upper bound to every variable in vars.

Template Parameters
DerivedAn Eigen Vector type with Variable as the scalar type.
Parameters
lbLower bound.
ubUpper bound.
varsThe decision variables.

◆ AddBoundingBoxConstraint() [6/6]

std::enable_if< std::is_same<typename Derived::Scalar, symbolic::Variable>::value && Derived::ColsAtCompileTime != 1, Binding<BoundingBoxConstraint> >::type AddBoundingBoxConstraint ( double  lb,
double  ub,
const Eigen::MatrixBase< Derived > &  vars 
)

Adds the same scalar lower and upper bound to every variable in vars.

Template Parameters
DerivedAn Eigen::Matrix with Variable as the scalar type. The matrix has unknown number of columns at compile time, or has more than one column.
Parameters
lbLower bound.
ubUpper bound.
varsThe decision variables.

◆ AddConstraint() [1/17]

Binding< Constraint > AddConstraint ( const Binding< Constraint > &  binding)

Adds a generic constraint to the program.

This should only be used if a more specific type of constraint is not available, as it may require the use of a significantly more expensive solver.

◆ AddConstraint() [2/17]

Binding< Constraint > AddConstraint ( const symbolic::Expression e,
double  lb,
double  ub 
)

Adds one row of constraint lb <= e <= ub where e is a symbolic expression.

Exceptions
std::exceptionif
  1. lb <= e <= ub is a trivial constraint such as 1 <= 2 <= 3.
  2. lb <= e <= ub is unsatisfiable such as 1 <= -5 <= 3
Parameters
eA symbolic expression of the the decision variables.
lbA scalar, the lower bound.
ubA scalar, the upper bound.

The resulting constraint may be a BoundingBoxConstraint, LinearConstraint, LinearEqualityConstraint, or ExpressionConstraint, depending on the arguments. Constraints of the form x == 1 (which could be created as a BoundingBoxConstraint or LinearEqualityConstraint) will be constructed as a LinearEqualityConstraint.

◆ AddConstraint() [3/17]

Binding<Constraint> AddConstraint ( const Eigen::Ref< const VectorX< symbolic::Expression >> &  v,
const Eigen::Ref< const Eigen::VectorXd > &  lb,
const Eigen::Ref< const Eigen::VectorXd > &  ub 
)

◆ AddConstraint() [4/17]

Binding< Constraint > AddConstraint ( const symbolic::Formula f)

Add a constraint represented by a symbolic formula to the program.

The input formula f can be of the following forms:

  1. e1 <= e2
  2. e1 >= e2
  3. e1 == e2
  4. A conjunction of relational formulas where each conjunct is a relational formula matched by 1, 2, or 3.

Note that first two cases might return an object of Binding<BoundingBoxConstraint>, Binding<LinearConstraint>, or Binding<ExpressionConstraint>, depending on f. Also the third case might return an object of Binding<LinearEqualityConstraint> or Binding<ExpressionConstraint>.

It throws an exception if

  1. f is not matched with one of the above patterns. Especially, strict inequalities (<, >) are not allowed.
  2. f is either a trivial constraint such as "1 <= 2" or an unsatisfiable constraint such as "2 <= 1".
  3. It is not possible to find numerical bounds of e1 and e2 where f = e1 ≃ e2. We allow e1 and e2 to be infinite but only if there are no other terms. For example, x <= ∞ is allowed. However, x - ∞ <= 0 is not allowed because x ↦ ∞ introduces nan in the evaluation.

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

A common use-case of this function is to add a constraint with the element-wise comparison between two Eigen matrices, using A.array() <= B.array(). See the following example.

Eigen::Matrix<double, 2, 2> A;
auto x = prog.NewContinuousVariables(2, "x");
... // set up A and b
prog.AddConstraint((A * x).array() <= b.array());

A formula in formulas can be of the following forms:

  1. e1 <= e2
  2. e1 >= e2
  3. e1 == e2

It throws an exception if AddConstraint(const symbolic::Formula& f) throws an exception for f ∈ formulas.

Template Parameters
DerivedAn Eigen Array type of Formula.

◆ AddConstraint() [5/17]

std::enable_if< is_eigen_scalar_same<Derived, symbolic::Formula>::value, Binding<Constraint> >::type AddConstraint ( const Eigen::ArrayBase< Derived > &  formulas)

◆ AddConstraint() [6/17]

auto AddConstraint ( std::shared_ptr< C >  con,
const VariableRefList vars 
)

Adds a generic constraint to the program.

This should only be used if a more specific type of constraint is not available, as it may require the use of a significantly more expensive solver.

◆ AddConstraint() [7/17]

auto AddConstraint ( std::shared_ptr< C >  con,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a generic constraint to the program.

This should only be used if a more specific type of constraint is not available, as it may require the use of a significantly more expensive solver.

◆ AddConstraint() [8/17]

Binding< LinearConstraint > AddConstraint ( const Binding< LinearConstraint > &  binding)

Adds linear constraints referencing potentially a subset of the decision variables (defined in the vars parameter).

◆ AddConstraint() [9/17]

Binding< LinearEqualityConstraint > AddConstraint ( const Binding< LinearEqualityConstraint > &  binding)

Adds linear equality constraints referencing potentially a subset of the decision variables.

◆ AddConstraint() [10/17]

Binding< BoundingBoxConstraint > AddConstraint ( const Binding< BoundingBoxConstraint > &  binding)

Adds bounding box constraints referencing potentially a subest of the decision variables.

Parameters
bindingBinds a BoundingBoxConstraint with some decision variables, such that binding.evaluator()->lower_bound()(i) <= binding.variables()(i) <= binding.evaluator().upper_bound()(i)

◆ AddConstraint() [11/17]

Binding< LorentzConeConstraint > AddConstraint ( const Binding< LorentzConeConstraint > &  binding)

Adds Lorentz cone constraint referencing potentially a subset of the decision variables.

The linear expression \( z=Ax+b \) is in the Lorentz cone. A vector \( z \in\mathbb{R}^n \) is in the Lorentz cone, if

\[ z_0 \ge \sqrt{z_1^2 + ... + z_{n-1}^2} \]

◆ AddConstraint() [12/17]

Adds a rotated Lorentz cone constraint referencing potentially a subset of decision variables.

The linear expression \( z=Ax+b \) is in rotated Lorentz cone. A vector \( z \in\mathbb{R}^n \) is in the rotated Lorentz cone, if

\[ z_0z_1 \ge z_2^2 + ... + z_{n-1}^2 \]

◆ AddConstraint() [13/17]

Adds a linear complementarity constraints referencing a subset of the decision variables.

◆ AddConstraint() [14/17]

Adds a positive semidefinite constraint on a symmetric matrix.

◆ AddConstraint() [15/17]

Binding< PositiveSemidefiniteConstraint > AddConstraint ( std::shared_ptr< PositiveSemidefiniteConstraint con,
const Eigen::Ref< const MatrixXDecisionVariable > &  symmetric_matrix_var 
)

Adds a positive semidefinite constraint on a symmetric matrix.

◆ AddConstraint() [16/17]

Adds a linear matrix inequality constraint to the program.

◆ AddConstraint() [17/17]

Binding< ExponentialConeConstraint > AddConstraint ( const Binding< ExponentialConeConstraint > &  binding)

Adds the exponential cone constraint that z = binding.evaluator()->A() * binding.variables() + binding.evaluator()->b() should be in the exponential cone.

Namely {(z₀, z₁, z₂) | z₀ ≥ z₁ * exp(z₂ / z₁), z₁ > 0}.

Parameters
bindingThe binding of ExponentialConeConstraint and its bound variables.

◆ AddCost() [1/9]

Binding< Cost > AddCost ( const Binding< Cost > &  binding)

Adds a generic cost to the optimization program.

◆ AddCost() [2/9]

auto AddCost ( const std::shared_ptr< C > &  obj,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a cost type to the optimization program.

Parameters
objThe added objective.
varsThe decision variables on which the cost depend.

◆ AddCost() [3/9]

auto AddCost ( const std::shared_ptr< C > &  obj,
const VariableRefList vars 
)

Adds a generic cost to the optimization program.

Parameters
objThe added objective.
varsThe decision variables on which the cost depend.

◆ AddCost() [4/9]

std::enable_if<internal::is_cost_functor_candidate<F>::value, Binding<Cost> >::type AddCost ( F &&  f,
const VariableRefList vars 
)

Adds a cost to the optimization program on a list of variables.

Template Parameters
Fit should define functions numInputs, numOutputs and eval. Check

◆ AddCost() [5/9]

std::enable_if<internal::is_cost_functor_candidate<F>::value, Binding<Cost> >::type AddCost ( F &&  f,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a cost to the optimization program on an Eigen::Vector containing decision variables.

Template Parameters
FType that defines functions numInputs, numOutputs and eval.

◆ AddCost() [6/9]

std::enable_if<internal::assert_if_is_constraint<F>::value, Binding<Cost> >::type AddCost ( F &&  ,
Vars &&   
)

Statically assert if a user inadvertently passes a binding-compatible Constraint.

Template Parameters
FThe type to check.

◆ AddCost() [7/9]

Binding< LinearCost > AddCost ( const Binding< LinearCost > &  binding)

Adds a cost term of the form c'*x.

Applied to a subset of the variables and pushes onto the linear cost data structure.

◆ AddCost() [8/9]

Binding< QuadraticCost > AddCost ( const Binding< QuadraticCost > &  binding)

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.

◆ AddCost() [9/9]

Binding< Cost > AddCost ( const symbolic::Expression e)

Adds a cost in the symbolic form.

Note that the constant part of the cost is ignored. So if you set e = x + 2, then only the cost on x is added, the constant term 2 is ignored.

Parameters
eThe linear or quadratic expression of the cost.
Precondition
e is linear or e is quadratic. Otherwise throws a runtime error.
Returns
The newly created cost, together with the bound variables.

◆ AddDecisionVariables()

void AddDecisionVariables ( const Eigen::Ref< const VectorXDecisionVariable > &  decision_variables)

Appends new variables to the end of the existing variables.

Parameters
decision_variablesThe newly added decision_variables.
Precondition
decision_variables should not intersect with the existing variables or indeterminates in the optimization program.
Each entry in decision_variables should not be a dummy variable.
Exceptions
std::runtime_errorif the preconditions are not satisfied.

◆ AddEqualityConstraintBetweenPolynomials()

void AddEqualityConstraintBetweenPolynomials ( const symbolic::Polynomial p1,
const symbolic::Polynomial p2 
)

Constraining that two polynomials are the same (i.e., they have the same coefficients for each monomial).

This function is often used in sum-of-squares optimization. We will impose the linear equality constraint that the coefficient of a monomial in p1 is the same as the coefficient of the same monomial in p2.

Parameters
p1Note that p1's indeterminates should have been registered as indeterminates in this MathematicalProgram object, and p1's coefficients are affine functions of decision variables in this MathematicalProgram object.
p2Note that p2's indeterminates should have been registered as indeterminates in this MathematicalProgram object, and p2's coefficients are affine functions of decision variables in this MathematicalProgram object.

◆ AddExponentialConeConstraint() [1/2]

Binding< ExponentialConeConstraint > AddExponentialConeConstraint ( const Eigen::Ref< const Eigen::SparseMatrix< double >> &  A,
const Eigen::Ref< const Eigen::Vector3d > &  b,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds an exponential cone constraint, that z = A * vars + b should be in the exponential cone.

Namely {z₀, z₁, z₂ | z₀ ≥ z₁ * exp(z₂ / z₁), z₁ > 0}.

Parameters
AThe A matrix in the documentation above. A must have 3 rows.
bThe b vector in the documentation above.
varsThe variables bound with this constraint.

◆ AddExponentialConeConstraint() [2/2]

Binding< ExponentialConeConstraint > AddExponentialConeConstraint ( const Eigen::Ref< const Vector3< symbolic::Expression >> &  z)

Add the constraint that z is in the exponential cone.

Parameters
zThe expression in the exponential cone.
Precondition
each entry in z is a linear expression of the decision variables.

◆ AddIndeterminates()

void AddIndeterminates ( const Eigen::Ref< const VectorXIndeterminate > &  new_indeterminates)

Adds indeterminates.

This method appends some indeterminates to the end of the program's old indeterminates.

Parameters
new_indeterminatesThe indeterminates to be appended to the program's old indeterminates.
Precondition
new_indeterminates should not intersect with the program's old indeterminates or decision variables.
Each entry in new_indeterminates should not be dummy.
Each entry in new_indeterminates should be of CONTINUOUS type.

◆ AddL2NormCost() [1/2]

Binding<QuadraticCost> AddL2NormCost ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const VariableRefList vars 
)

Adds a cost term of the form | Ax - b |^2.

◆ AddL2NormCost() [2/2]

Binding<QuadraticCost> AddL2NormCost ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a cost term of the form | Ax - b |^2.

◆ AddLinearComplementarityConstraint() [1/2]

Binding<LinearComplementarityConstraint> AddLinearComplementarityConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  M,
const Eigen::Ref< const Eigen::VectorXd > &  q,
const VariableRefList vars 
)

Adds a linear complementarity constraints referencing a subset of the decision variables.

◆ AddLinearComplementarityConstraint() [2/2]

Binding< LinearComplementarityConstraint > AddLinearComplementarityConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  M,
const Eigen::Ref< const Eigen::VectorXd > &  q,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a linear complementarity constraints referencing a subset of the decision variables.

◆ AddLinearConstraint() [1/8]

Binding<LinearConstraint> AddLinearConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  lb,
const Eigen::Ref< const Eigen::VectorXd > &  ub,
const VariableRefList vars 
)

Adds linear constraints referencing potentially a subset of the decision variables (defined in the vars parameter).

◆ AddLinearConstraint() [2/8]

Binding< LinearConstraint > AddLinearConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  lb,
const Eigen::Ref< const Eigen::VectorXd > &  ub,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds linear constraints referencing potentially a subset of the decision variables (defined in the vars parameter).

◆ AddLinearConstraint() [3/8]

Binding<LinearConstraint> AddLinearConstraint ( const Eigen::Ref< const Eigen::RowVectorXd > &  a,
double  lb,
double  ub,
const VariableRefList vars 
)

Adds one row of linear constraint referencing potentially a subset of the decision variables (defined in the vars parameter).

lb <= a*vars <= ub

Parameters
aA row vector.
lbA scalar, the lower bound.
ubA scalar, the upper bound.
varsThe decision variables on which to impose the linear constraint.

◆ AddLinearConstraint() [4/8]

Binding<LinearConstraint> AddLinearConstraint ( const Eigen::Ref< const Eigen::RowVectorXd > &  a,
double  lb,
double  ub,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds one row of linear constraint referencing potentially a subset of the decision variables (defined in the vars parameter).

lb <= a*vars <= ub

Parameters
aA row vector.
lbA scalar, the lower bound.
ubA scalar, the upper bound.
varsThe decision variables on which to impose the linear constraint.

◆ AddLinearConstraint() [5/8]

Binding< LinearConstraint > AddLinearConstraint ( const symbolic::Expression e,
double  lb,
double  ub 
)

Adds one row of linear constraint lb <= e <= ub where e is a symbolic expression.

Exceptions
std::exceptionif
  1. e is a non-linear expression.
  2. lb <= e <= ub is a trivial constraint such as 1 <= 2 <= 3.
  3. lb <= e <= ub is unsatisfiable such as 1 <= -5 <= 3
Parameters
eA linear symbolic expression in the form of c0 + c1 * v1 + ... + cn * vn where c_i is a constant and @v_i is a variable.
lbA scalar, the lower bound.
ubA scalar, the upper bound.

◆ AddLinearConstraint() [6/8]

Binding<LinearConstraint> AddLinearConstraint ( const Eigen::Ref< const VectorX< symbolic::Expression >> &  v,
const Eigen::Ref< const Eigen::VectorXd > &  lb,
const Eigen::Ref< const Eigen::VectorXd > &  ub 
)

Adds linear constraints represented by symbolic expressions to the program.

It throws if @v includes a non-linear expression or lb <= v <= ub includes trivial/unsatisfiable constraints.

◆ AddLinearConstraint() [7/8]

Binding< LinearConstraint > AddLinearConstraint ( const symbolic::Formula f)

Add a linear constraint represented by a symbolic formula to the program.

The input formula f can be of the following forms:

  1. e1 <= e2
  2. e1 >= e2
  3. e1 == e2
  4. A conjunction of relational formulas where each conjunct is a relational formula matched by 1, 2, or 3.

Note that first two cases might return an object of Binding<BoundingBoxConstraint> depending on f. Also the third case returns an object of Binding<LinearEqualityConstraint>.

It throws an exception if

  1. f is not matched with one of the above patterns. Especially, strict inequalities (<, >) are not allowed.
  2. f includes a non-linear expression.
  3. f is either a trivial constraint such as "1 <= 2" or an unsatisfiable constraint such as "2 <= 1".
  4. It is not possible to find numerical bounds of e1 and e2 where f = e1 ≃ e2. We allow e1 and e2 to be infinite but only if there are no other terms. For example, x <= ∞ is allowed. However, x - ∞ <= 0 is not allowed because x ↦ ∞ introduces nan in the evaluation.

◆ AddLinearConstraint() [8/8]

std::enable_if< is_eigen_scalar_same<Derived, symbolic::Formula>::value, Binding<LinearConstraint> >::type AddLinearConstraint ( const Eigen::ArrayBase< Derived > &  formulas)

Add a linear constraint represented by an Eigen::Array<symbolic::Formula> to the program.

A common use-case of this function is to add a linear constraint with the element-wise comparison between two Eigen matrices, using A.array() <= B.array(). See the following example.

Eigen::Matrix<double, 2, 2> A;
auto x = prog.NewContinuousVariables(2, "x");
... // set up A and b
prog.AddLinearConstraint((A * x).array() <= b.array());

A formula in formulas can be of the following forms:

  1. e1 <= e2
  2. e1 >= e2
  3. e1 == e2

It throws an exception if AddLinearConstraint(const symbolic::Formula& f) throws an exception for f ∈ formulas.

Template Parameters
DerivedAn Eigen Array type of Formula.

◆ AddLinearCost() [1/4]

Binding< LinearCost > AddLinearCost ( const symbolic::Expression e)

Adds a linear cost term of the form a'*x + b.

Parameters
eA linear symbolic expression.
Precondition
e is a linear expression a'*x + b, where each entry of x is a decision variable in the mathematical program.
Returns
The newly added linear constraint, together with the bound variables.

◆ AddLinearCost() [2/4]

Binding<LinearCost> AddLinearCost ( const Eigen::Ref< const Eigen::VectorXd > &  a,
double  b,
const VariableRefList 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.

◆ AddLinearCost() [3/4]

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 + b.

Applied to a subset of the variables and pushes onto the linear cost data structure.

◆ AddLinearCost() [4/4]

Binding<LinearCost> AddLinearCost ( const Eigen::Ref< const Eigen::VectorXd > &  a,
const VarType 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.

◆ AddLinearEqualityConstraint() [1/8]

Binding< LinearEqualityConstraint > AddLinearEqualityConstraint ( const symbolic::Expression e,
double  b 
)

Adds one row of linear constraint e = b where e is a symbolic expression.

Exceptions
std::exceptionif
  1. e is a non-linear expression.
  2. e is a constant.
Parameters
eA linear symbolic expression in the form of c0 + c1 * x1 + ... + cn * xn where c_i is a constant and @x_i is a variable.
bA scalar.
Returns
The newly added linear equality constraint, together with the bound variable.

◆ AddLinearEqualityConstraint() [2/8]

Binding< LinearEqualityConstraint > AddLinearEqualityConstraint ( const symbolic::Formula f)

Adds a linear equality constraint represented by a symbolic formula to the program.

The input formula f is either an equality formula (e1 == e2) or a conjunction of equality formulas.

It throws an exception if

  1. f is neither an equality formula nor a conjunction of equalities.
  2. f includes a non-linear expression.

◆ AddLinearEqualityConstraint() [3/8]

std::enable_if< is_eigen_vector_expression_double_pair<DerivedV, DerivedB>::value, Binding<LinearEqualityConstraint> >::type AddLinearEqualityConstraint ( const Eigen::MatrixBase< DerivedV > &  v,
const Eigen::MatrixBase< DerivedB > &  b 
)

Adds linear equality constraints \( v = b \), where v(i) is a symbolic linear expression.

Exceptions
std::exceptionif
  1. v(i) is a non-linear expression.
  2. v(i) is a constant.
Template Parameters
DerivedVAn Eigen Matrix type of Expression. A column vector.
DerivedBAn Eigen Matrix type of double. A column vector.
Parameters
vv(i) is a linear symbolic expression in the form of c0 + c1 * x1 + ... + cn * xn where ci is a constant and @xi is a variable.
bA vector of doubles.
Returns
The newly added linear equality constraint, together with the bound variables.

◆ AddLinearEqualityConstraint() [4/8]

std::enable_if< is_eigen_nonvector_expression_double_pair<DerivedV, DerivedB>::value, Binding<LinearEqualityConstraint> >::type AddLinearEqualityConstraint ( const Eigen::MatrixBase< DerivedV > &  V,
const Eigen::MatrixBase< DerivedB > &  B,
bool  lower_triangle = false 
)

Adds a linear equality constraint for a matrix of linear expression V, such that V(i, j) = B(i, j).

If V is a symmetric matrix, then the user may only want to constrain the lower triangular part of V. This function is meant to provide convenience to the user, it incurs additional copy and memory allocation. For faster speed, add each column of the matrix equality in a for loop.

Template Parameters
DerivedVAn Eigen Matrix type of Expression. The number of columns at compile time should not be 1.
DerivedBAn Eigen Matrix type of double.
Parameters
VAn Eigen Matrix of symbolic expressions. V(i, j) should be a linear expression.
BAn Eigen Matrix of doubles.
lower_triangleIf true, then only the lower triangular part of V is constrained, otherwise the whole matrix V is constrained.
Default: is false.
Returns
The newly added linear equality constraint, together with the bound variables.

◆ AddLinearEqualityConstraint() [5/8]

Binding<LinearEqualityConstraint> AddLinearEqualityConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  Aeq,
const Eigen::Ref< const Eigen::VectorXd > &  beq,
const VariableRefList vars 
)

AddLinearEqualityConstraint.

Adds linear equality constraints referencing potentially a subset of the decision variables.

Example: to add two equality constraints which only depend on two of the elements of x, you could use

auto x = prog.NewContinuousVariables(6,"myvar");
Eigen::Matrix2d Aeq;
Aeq << -1, 2,
1, 1;
Eigen::Vector2d beq(1, 3);
prog.AddLinearEqualityConstraint(Aeq, beq, {x.segment<1>(2),
x.segment<1>(5)});

The code above imposes constraints

\[-x(2) + 2x(5) = 1 \]

\[ x(2) + x(5) = 3 \]

◆ AddLinearEqualityConstraint() [6/8]

Binding< LinearEqualityConstraint > AddLinearEqualityConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  Aeq,
const Eigen::Ref< const Eigen::VectorXd > &  beq,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

AddLinearEqualityConstraint.

Adds linear equality constraints referencing potentially a subset of the decision variables.

Example: to add two equality constraints which only depend on two of the elements of x, you could use

auto x = prog.NewContinuousVariables(6,"myvar");
Eigen::Matrix2d Aeq;
Aeq << -1, 2,
1, 1;
Eigen::Vector2d beq(1, 3);
// Imposes constraint
// -x(0) + 2x(1) = 1
// x(0) + x(1) = 3
prog.AddLinearEqualityConstraint(Aeq, beq, x.head<2>());

◆ AddLinearEqualityConstraint() [7/8]

Binding<LinearEqualityConstraint> AddLinearEqualityConstraint ( const Eigen::Ref< const Eigen::RowVectorXd > &  a,
double  beq,
const VariableRefList vars 
)

Adds one row of linear equality constraint referencing potentially a subset of decision variables.

\[ ax = beq \]

Parameters
aA row vector.
beqA scalar.
varsThe decision variables on which the constraint is imposed.

◆ AddLinearEqualityConstraint() [8/8]

Binding<LinearEqualityConstraint> AddLinearEqualityConstraint ( const Eigen::Ref< const Eigen::RowVectorXd > &  a,
double  beq,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds one row of linear equality constraint referencing potentially a subset of decision variables.

\[ ax = beq \]

Parameters
aA row vector.
beqA scalar.
varsThe decision variables on which the constraint is imposed.

◆ AddLinearMatrixInequalityConstraint() [1/2]

Binding<LinearMatrixInequalityConstraint> AddLinearMatrixInequalityConstraint ( const std::vector< Eigen::Ref< const Eigen::MatrixXd >> &  F,
const VariableRefList vars 
)

Adds a linear matrix inequality constraint to the program.

◆ AddLinearMatrixInequalityConstraint() [2/2]

Binding< LinearMatrixInequalityConstraint > AddLinearMatrixInequalityConstraint ( const std::vector< Eigen::Ref< const Eigen::MatrixXd >> &  F,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a linear matrix inequality constraint to the program.

◆ AddLorentzConeConstraint() [1/6]

Binding<LorentzConeConstraint> AddLorentzConeConstraint ( const Eigen::Ref< const VectorX< symbolic::Expression >> &  v)

Adds Lorentz cone constraint referencing potentially a subset of the decision variables.

Parameters
vAn Eigen::Vector of symbolic::Expression. Constraining that

\[ v_0 \ge \sqrt{v_1^2 + ... + v_{n-1}^2} \]

Returns
The newly constructed Lorentz cone constraint with the bounded variables.

◆ AddLorentzConeConstraint() [2/6]

Binding< LorentzConeConstraint > AddLorentzConeConstraint ( const symbolic::Expression linear_expression,
const symbolic::Expression quadratic_expression,
double  tol = 0 
)

Adds Lorentz cone constraint on the linear expression v1 and quadratic expression v2, such that v1 >= sqrt(v2)

Parameters
linear_expressionThe linear expression v1.
quadratic_expressionThe quadratic expression v2.
tolThe tolerance to determine if the matrix in v2 is positive semidefinite or not.
See also
DecomposePositiveQuadraticForm for more explanation.
Default: is 0.
Return values
bindingThe newly added Lorentz cone constraint, together with the bound variables.
Precondition
  1. v1 is a linear expression, in the form of c'*x + d.
  2. v2 is a quadratic expression, in the form of
             x'*Q*x + b'x + a
       
    Also the quadratic expression has to be convex, namely Q is a positive semidefinite matrix, and the quadratic expression needs to be non-negative for any x.
Exceptions
std::runtime_errorif the preconditions are not satisfied.

Notice this constraint is equivalent to the vector [z;y] is within a Lorentz cone, where

 z = v1
 y = R * x + d

while (R, d) satisfies y'*y = x'*Q*x + b'*x + a

◆ AddLorentzConeConstraint() [3/6]

Binding<LorentzConeConstraint> AddLorentzConeConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const VariableRefList vars 
)

Adds Lorentz cone constraint referencing potentially a subset of the decision variables (defined in the vars parameter).

The linear expression \( z=Ax+b \) is in the Lorentz cone. A vector \( z \in\mathbb{R}^n \) is in the Lorentz cone, if

\[ z_0 \ge \sqrt{z_1^2 + ... + z_{n-1}^2} \]

Parameters
AA \(\mathbb{R}^{n\times m}\) matrix, whose number of columns equals to the size of the decision variables.
bA \(\mathbb{R}^n\) vector, whose number of rows equals to the size of the decision variables.
varsThe list of \( m \) decision variables.
Returns
The newly added Lorentz cone constraint.

◆ AddLorentzConeConstraint() [4/6]

Binding< LorentzConeConstraint > AddLorentzConeConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds Lorentz cone constraint referencing potentially a subset of the decision variables (defined in the vars parameter).

The linear expression \( z=Ax+b \) is in the Lorentz cone. A vector \( z \in\mathbb{R}^n \) is in the Lorentz cone, if

\[ z_0 \ge \sqrt{z_1^2 + ... + z_{n-1}^2} \]

Parameters
AA \(\mathbb{R}^{n\times m}\) matrix, whose number of columns equals to the size of the decision variables.
bA \(\mathbb{R}^n\) vector, whose number of rows equals to the size of the decision variables.
varsThe Eigen vector of \( m \) decision variables.
Returns
The newly added Lorentz cone constraint.

◆ AddLorentzConeConstraint() [5/6]

Binding<LorentzConeConstraint> AddLorentzConeConstraint ( const VariableRefList vars)

Imposes that a vector \( x\in\mathbb{R}^m \) lies in Lorentz cone.

Namely

\[ x_0 \ge \sqrt{x_1^2 + .. + x_{m-1}^2} \]

Parameters
varsThe stacked column of vars should lie within the Lorentz cone.
Returns
The newly added Lorentz cone constraint.

◆ AddLorentzConeConstraint() [6/6]

Binding<LorentzConeConstraint> AddLorentzConeConstraint ( const Eigen::MatrixBase< VectorDecisionVariable< rows >> &  vars)

Imposes that a vector \( x\in\mathbb{R}^m \) lies in Lorentz cone.

Namely

\[ x_0 \ge \sqrt{x_1^2 + .. + x_{m-1}^2} \]

Parameters
varsThe stacked column of vars should lie within the Lorentz cone.
Returns
The newly added Lorentz cone constraint.

◆ AddMaximizeGeometricMeanCost() [1/2]

void AddMaximizeGeometricMeanCost ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const Eigen::Ref< const VectorX< symbolic::Variable >> &  x 
)

An overloaded version of maximize_geometric_mean.

Precondition
A.rows() == b.rows(), A.rows() >= 2.

◆ AddMaximizeGeometricMeanCost() [2/2]

void AddMaximizeGeometricMeanCost ( const Eigen::Ref< const VectorX< symbolic::Variable >> &  x,
double  c = 1.0 
)

An overloaded version of maximize_geometric_mean.

We add the cost to maximize the geometric mean of x, i.e., c*power(∏ᵢx(i), 1/n).

Parameters
cThe positive coefficient of the geometric mean cost,
Default: is 1.
Precondition
x.rows() >= 2.
c > 0.

◆ AddMaximizeLogDeterminantSymmetricMatrixCost()

void AddMaximizeLogDeterminantSymmetricMatrixCost ( const Eigen::Ref< const MatrixX< symbolic::Expression >> &  X)

Adds the cost to maximize the log determinant of symmetric matrix X.

log(det(X)) is a concave function of X, so we can maximize it through convex optimization. In order to do that, we introduce slack variables t, and a lower triangular matrix Z, with the constraints ⌈X Z⌉ is positive semidifinite. ⌊Zᵀ diag(Z)⌋ log(Z(i, i)) >= t(i) and we will minimize -∑ᵢt(i).

Parameters
XA symmetric positive semidefinite matrix X, whose log(det(X)) will be maximized.
Precondition
X is a symmetric matrix.
Note
The constraint log(Z(i, i)) >= t(i) is imposed as an exponential cone constraint. Please make sure your have a solver that supports exponential cone constraint (currently SCS does).

◆ AddPolynomialConstraint() [1/2]

Binding<Constraint> AddPolynomialConstraint ( const VectorXPoly polynomials,
const std::vector< Polynomiald::VarType > &  poly_vars,
const Eigen::VectorXd &  lb,
const Eigen::VectorXd &  ub,
const VariableRefList vars 
)

Adds a polynomial constraint to the program referencing a subset of the decision variables (defined in the vars parameter).

◆ AddPolynomialConstraint() [2/2]

Binding< Constraint > AddPolynomialConstraint ( const VectorXPoly polynomials,
const std::vector< Polynomiald::VarType > &  poly_vars,
const Eigen::VectorXd &  lb,
const Eigen::VectorXd &  ub,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a polynomial constraint to the program referencing a subset of the decision variables (defined in the vars parameter).

◆ AddPolynomialCost()

Binding< PolynomialCost > AddPolynomialCost ( const symbolic::Expression e)

Adds a cost term in the polynomial form.

Parameters
eA symbolic expression in the polynomial form.
Returns
The newly created cost and the bound variables.

◆ AddPositiveDiagonallyDominantMatrixConstraint()

MatrixX< symbolic::Expression > AddPositiveDiagonallyDominantMatrixConstraint ( const Eigen::Ref< const MatrixX< symbolic::Expression >> &  X)

Adds the constraint that a symmetric matrix is diagonally dominant with non-negative diagonal entries.

A symmetric matrix X is diagonally dominant with non-negative diagonal entries if X(i, i) >= ∑ⱼ |X(i, j)| ∀ j ≠ i namely in each row, the diagonal entry is larger than the sum of the absolute values of all other entries in the same row. A matrix being diagonally dominant with non-negative diagonals is a sufficient (but not necessary) condition of a matrix being positive semidefinite. Internally we will create a matrix Y as slack variables, such that Y(i, j) represents the absolute value |X(i, j)| ∀ j ≠ i. The diagonal entries Y(i, i) = X(i, i) The users can 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

Parameters
XThe matrix X. We will use 0.5(X+Xᵀ) as the "symmetric version" of X.
Returns
Y The slack variable. Y(i, j) represents |X(i, j)| ∀ j ≠ i, with the constraint Y(i, j) >= X(i, j) and Y(i, j) >= -X(i, j). Y is a symmetric matrix. The diagonal entries Y(i, i) = X(i, i)

◆ AddPositiveSemidefiniteConstraint() [1/2]

Binding< PositiveSemidefiniteConstraint > AddPositiveSemidefiniteConstraint ( const Eigen::Ref< const MatrixXDecisionVariable > &  symmetric_matrix_var)

Adds a positive semidefinite constraint on a symmetric matrix.

Exceptions
std::runtime_errorin Debug mode if symmetric_matrix_var is not symmetric.
Parameters
symmetric_matrix_varA symmetric MatrixDecisionVariable object.

◆ AddPositiveSemidefiniteConstraint() [2/2]

std::enable_if< std::is_same<typename Derived::Scalar, symbolic::Expression>::value, Binding<PositiveSemidefiniteConstraint> >::type AddPositiveSemidefiniteConstraint ( const Eigen::MatrixBase< Derived > &  e)

Adds a positive semidefinite constraint on a symmetric matrix of symbolic expressions e.

We create a new symmetric matrix of variables M being positive semidefinite, with the linear equality constraint e == M.

Template Parameters
DerivedAn Eigen Matrix of symbolic expressions.
Parameters
eImposes constraint "e is positive semidefinite".
Precondition
{1. e is symmetric.
  1. e(i, j) is linear for all i, j }
Returns
The newly added positive semidefinite constraint, with the bound variable M that are also newly added.

◆ AddQuadraticCost() [1/4]

Binding< QuadraticCost > AddQuadraticCost ( const symbolic::Expression e)

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.

Parameters
eA quadratic symbolic expression.
Exceptions
std::runtimeerror if the expression is not quadratic.
Returns
The newly added cost together with the bound variables.

◆ AddQuadraticCost() [2/4]

Binding<QuadraticCost> AddQuadraticCost ( const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const VariableRefList vars 
)

Adds a cost term of the form 0.5*x'*Q*x + b'x.

Applied to subset of the variables.

◆ AddQuadraticCost() [3/4]

Binding< QuadraticCost > AddQuadraticCost ( const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::VectorXd > &  b,
double  c,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a cost term of the form 0.5*x'*Q*x + b'x + c Applied to subset of the variables.

◆ AddQuadraticCost() [4/4]

Binding< QuadraticCost > AddQuadraticCost ( const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a cost term of the form 0.5*x'*Q*x + b'x Applied to subset of the variables.

◆ AddQuadraticErrorCost() [1/2]

Binding<QuadraticCost> AddQuadraticErrorCost ( const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::VectorXd > &  x_desired,
const VariableRefList vars 
)

Adds a cost term of the form (x-x_desired)'Q(x-x_desired).

◆ AddQuadraticErrorCost() [2/2]

Binding< QuadraticCost > AddQuadraticErrorCost ( const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::VectorXd > &  x_desired,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a cost term of the form (x-x_desired)'Q(x-x_desired).

◆ AddRotatedLorentzConeConstraint() [1/6]

Binding< RotatedLorentzConeConstraint > AddRotatedLorentzConeConstraint ( const symbolic::Expression linear_expression1,
const symbolic::Expression linear_expression2,
const symbolic::Expression quadratic_expression,
double  tol = 0 
)

Adds rotated Lorentz cone constraint on the linear expression v1, v2 and quadratic expression u, such that v1 * v2 >= u, v1 >= 0, v2 >= 0.

Parameters
linear_expression1The linear expression v1.
linear_expression2The linear expression v2.
quadratic_expressionThe quadratic expression u.
tolThe tolerance to determine if the matrix in v2 is positive semidefinite or not.
See also
DecomposePositiveQuadraticForm for more explanation.
Default: is 0.
Return values
bindingThe newly added rotated Lorentz cone constraint, together with the bound variables.
Precondition
  1. linear_expression1 is a linear (affine) expression, in the form of v1 = c1'*x + d1.
  2. linear_expression2 is a linear (affine) expression, in the form of v2 = c2'*x + d2.
  1. quadratic_expression is a quadratic expression, in the form of
             u = x'*Q*x + b'x + a
       
    Also the quadratic expression has to be convex, namely Q is a positive semidefinite matrix, and the quadratic expression needs to be non-negative for any x.
Exceptions
std::runtime_errorif the preconditions are not satisfied.

◆ AddRotatedLorentzConeConstraint() [2/6]

Binding<RotatedLorentzConeConstraint> AddRotatedLorentzConeConstraint ( const Eigen::Ref< const VectorX< symbolic::Expression >> &  v)

Adds a constraint that a symbolic expression.

Parameters
vis in the rotated Lorentz cone, i.e.,

\[ v_0v_1 \ge v_2^2 + ... + v_{n-1}^2\\ v_0 \ge 0, v_1 \ge 0 \]

vA linear expression of variables, \( v = A x + b\), where \( A, b \) are given matrices of the correct size, \( x \) is the vector of decision variables.
Return values
bindingThe newly added rotated Lorentz cone constraint, together with the bound variables.

◆ AddRotatedLorentzConeConstraint() [3/6]

Binding<RotatedLorentzConeConstraint> AddRotatedLorentzConeConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const VariableRefList vars 
)

Adds a rotated Lorentz cone constraint referencing potentially a subset of decision variables, The linear expression \( z=Ax+b \) is in rotated Lorentz cone.

A vector \( z \in\mathbb{R}^n \) is in the rotated Lorentz cone, if

\[ z_0z_1 \ge z_2^2 + ... + z_{n-1}^2 \]

where \( A\in\mathbb{R}^{n\times m}, b\in\mathbb{R}^n\) are given matrices.

Parameters
AA matrix whose number of columns equals to the size of the decision variables.
bA vector whose number of rows equals to the size fo the decision variables.
varsThe decision variables on which the constraint is imposed.

◆ AddRotatedLorentzConeConstraint() [4/6]

Binding< RotatedLorentzConeConstraint > AddRotatedLorentzConeConstraint ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
const Eigen::Ref< const VectorXDecisionVariable > &  vars 
)

Adds a rotated Lorentz cone constraint referencing potentially a subset of decision variables, The linear expression \( z=Ax+b \) is in rotated Lorentz cone.

A vector \( z \in\mathbb{R}^n \) is in the rotated Lorentz cone, if

\[ z_0z_1 \ge z_2^2 + ... + z_{n-1}^2 \]

where \( A\in\mathbb{R}^{n\times m}, b\in\mathbb{R}^n\) are given matrices.

Parameters
AA matrix whose number of columns equals to the size of the decision variables.
bA vector whose number of rows equals to the size fo the decision variables.
varsThe decision variables on which the constraint is imposed.

◆ AddRotatedLorentzConeConstraint() [5/6]

Binding<RotatedLorentzConeConstraint> AddRotatedLorentzConeConstraint ( const VariableRefList vars)

Impose that a vector \( x\in\mathbb{R}^m \) is in rotated Lorentz cone.

Namely

\[ x_0 x_1 \ge x_2^2 + ... + x_{m-1}^2\\ x_0 \ge 0, x_1 \ge 0 \]

Parameters
varsThe stacked column of vars lies in the rotated Lorentz cone.
Returns
The newly added rotated Lorentz cone constraint.

◆ AddRotatedLorentzConeConstraint() [6/6]

Binding<RotatedLorentzConeConstraint> AddRotatedLorentzConeConstraint ( const Eigen::MatrixBase< VectorDecisionVariable< rows >> &  vars)

Impose that a vector \( x\in\mathbb{R}^m \) is in rotated Lorentz cone.

Namely

\[ x_0 x_1 \ge x_2^2 + ... + x_{m-1}^2\\ x_0 \ge 0, x_1 \ge 0 \]

Parameters
varsThe stacked column of vars lies in the rotated Lorentz cone.
Returns
The newly added rotated Lorentz cone constraint.

◆ AddScaledDiagonallyDominantMatrixConstraint() [1/2]

std::vector< std::vector< Matrix2< symbolic::Expression > > > AddScaledDiagonallyDominantMatrixConstraint ( const Eigen::Ref< const MatrixX< symbolic::Expression >> &  X)

This is an overloaded variant of scaled diagonally dominant matrix constraint.

Parameters
XThe matrix X to be constrained scaled diagonally dominant. X.
Precondition
X(i, j) should be a linear expression of decision variables.
Returns
M A vector of vectors of 2 x 2 symmetric matrices M. For i < j, M[i][j] is
[Mⁱʲ(i, i), Mⁱʲ(i, j)]
[Mⁱʲ(i, j), Mⁱʲ(j, j)].
Note that M[i][j](0, 1) = Mⁱʲ(i, j) = (X(i, j) + X(j, i)) / 2 for i >= j, M[i][j] is the zero matrix.

◆ AddScaledDiagonallyDominantMatrixConstraint() [2/2]

std::vector< std::vector< Matrix2< symbolic::Variable > > > AddScaledDiagonallyDominantMatrixConstraint ( const Eigen::Ref< const MatrixX< symbolic::Variable >> &  X)

This is an overloaded variant of scaled diagonally dominant matrix constraint.

Parameters
XThe symmetric matrix X to be constrained scaled diagonally dominant.
Returns
M For i < j M[i][j] contains the slack variables, mentioned in scaled diagonally dominant matrix constraint. For i >= j, M[i][j] contains dummy variables.

◆ AddSosConstraint() [1/4]

MatrixXDecisionVariable AddSosConstraint ( const symbolic::Polynomial p,
const Eigen::Ref< const VectorX< symbolic::Monomial >> &  monomial_basis 
)

Adds constraints that a given polynomial p is a sums-of-squares (SOS), that is, p can be decomposed into mᵀQm, where m is the monomial_basis.

It returns the coefficients matrix Q, which is positive semidefinite.

◆ AddSosConstraint() [2/4]

pair< MatrixXDecisionVariable, VectorX< symbolic::Monomial > > AddSosConstraint ( const symbolic::Polynomial p)

Adds constraints that a given polynomial p is a sums-of-squares (SOS), that is, p can be decomposed into mᵀQm, where m is a monomial basis selected from the sparsity of p.

It returns a pair of constraint bindings expressing:

  • The coefficients matrix Q, which is positive semidefinite.
  • The monomial basis m.

◆ AddSosConstraint() [3/4]

MatrixXDecisionVariable AddSosConstraint ( const symbolic::Expression e,
const Eigen::Ref< const VectorX< symbolic::Monomial >> &  monomial_basis 
)

Adds constraints that a given symbolic expression e is a sums-of-squares (SOS), that is, p can be decomposed into mᵀQm, where m is the monomial_basis.

Note that it decomposes e into a polynomial with respect to indeterminates() in this mathematical program. It returns the coefficients matrix Q, which is positive semidefinite.

◆ AddSosConstraint() [4/4]

pair< MatrixXDecisionVariable, VectorX< symbolic::Monomial > > AddSosConstraint ( const symbolic::Expression e)

Adds constraints that a given symbolic expression e is a sums-of-squares (SOS), that is, e can be decomposed into mᵀQm.

Note that it decomposes e into a polynomial with respect to indeterminates() in this mathematical program. It returns a pair expressing:

  • The coefficients matrix Q, which is positive semidefinite.
  • The monomial basis m.

◆ AddVisualizationCallback() [1/2]

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.
Parameters
callbacka std::function that accepts an Eigen::Vector of doubles representing the bound decision variables.
varsthe decision variables that should be passed to the callback.

◆ AddVisualizationCallback() [2/2]

Binding<VisualizationCallback> AddVisualizationCallback ( const VisualizationCallback::CallbackFunction callback,
const VariableRefList 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.
Parameters
callbacka std::function that accepts an Eigen::Vector of doubles representing the for the bound decision variables.
varsthe decision variables that should be passed to the callback.

◆ bounding_box_constraints()

const std::vector<Binding<BoundingBoxConstraint> >& bounding_box_constraints ( ) const

Getter for all bounding box constraints.

◆ Clone()

std::unique_ptr< MathematicalProgram > Clone ( ) const

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.

Return values
new_prog.The newly constructed mathematical program.

◆ decision_variable()

const symbolic::Variable& decision_variable ( int  i) const

Getter for the decision variable with index i in the program.

◆ decision_variable_index()

const std::unordered_map<symbolic::Variable::Id, int>& decision_variable_index ( ) const

Returns the mapping from a decision variable to its index in the vector, containing all the decision variables in the optimization program.

◆ decision_variables()

const VectorXDecisionVariable& decision_variables ( ) const

Getter for all decision variables in the program.

◆ EvalBinding()

std::enable_if<is_eigen_vector<DerivedX>::value, VectorX<typename DerivedX::Scalar> >::type EvalBinding ( const Binding< C > &  binding,
const Eigen::MatrixBase< DerivedX > &  prog_var_vals 
) const

Evaluates the value of some binding, for some input value for all decision variables.

Parameters
bindingA Binding whose variables are decision variables in this program.
prog_var_valsThe value of all the decision variables in this program.
Exceptions
std::logic_errorif the size of prog_var_vals is invalid.

◆ EvalBindingAtInitialGuess()

Eigen::VectorXd EvalBindingAtInitialGuess ( const Binding< C > &  binding) const

Evaluates the evaluator in binding at the initial guess.

Returns
The value of binding at the initial guess.

◆ EvalBindings()

std::enable_if<is_eigen_vector<DerivedX>::value, VectorX<typename DerivedX::Scalar> >::type EvalBindings ( const std::vector< Binding< C >> &  bindings,
const Eigen::MatrixBase< DerivedX > &  prog_var_vals 
) const

Evaluates a set of bindings (plural version of EvalBinding).

Parameters
bindingsList of bindings.
prog
prog_var_valsThe value of all the decision variables in this program.
Returns
All binding values, concatenated into a single vector.
Exceptions
std::logic_errorif the size of prog_var_vals is invalid.

◆ EvalVisualizationCallbacks()

void EvalVisualizationCallbacks ( const Eigen::Ref< const Eigen::VectorXd > &  prog_var_vals) const

Evaluates all visualization callbacks registered with the MathematicalProgram.

Parameters
prog_var_valsThe value of all the decision variables in this program.
Exceptions
std::logic_errorif the size does not match.

◆ exponential_cone_constraints()

const std::vector<Binding<ExponentialConeConstraint> >& exponential_cone_constraints ( ) const

Getter for exponential cone constraints.

◆ FindDecisionVariableIndex()

int FindDecisionVariableIndex ( const symbolic::Variable var) const

Returns the index of the decision variable.

Internally the solvers thinks all variables are stored in an array, and it accesses each individual variable using its index. This index is used when adding constraints and costs for each solver.

Precondition
{var is a decision variable in the mathematical program, otherwise this function throws a runtime error.}

◆ FindDecisionVariableIndices()

std::vector< int > FindDecisionVariableIndices ( const Eigen::Ref< const VectorXDecisionVariable > &  vars) const

Returns the indices of the decision variables.

Internally the solvers thinks all variables are stored in an array, and it accesses each individual variable using its index. This index is used when adding constraints and costs for each solver.

Precondition
{vars are decision variables in the mathematical program, otherwise this function throws a runtime error.}

◆ FindIndeterminateIndex()

size_t FindIndeterminateIndex ( const symbolic::Variable var) const

Returns the index of the indeterminate.

Internally a solver thinks all indeterminates are stored in an array, and it accesses each individual indeterminate using its index. This index is used when adding constraints and costs for each solver.

Precondition
var is a indeterminate in the mathematical program, otherwise this function throws a runtime error.

◆ generic_constraints()

const std::vector<Binding<Constraint> >& generic_constraints ( ) const

Getter for all generic constraints.

◆ generic_costs()

const std::vector<Binding<Cost> >& generic_costs ( ) const

Getter for all generic costs.

◆ GetAllConstraints()

std::vector<Binding<Constraint> > GetAllConstraints ( ) const

Getter for returning all constraints.

Returns
Vector of all constraint bindings.
Note
The group ordering may change as more constraint types are added.

◆ GetAllCosts()

std::vector<Binding<Cost> > GetAllCosts ( ) const

Getter returning all costs.

Returns
Vector of all cost bindings.
Note
The group ordering may change as more cost types are added.

◆ GetAllLinearConstraints()

std::vector<Binding<LinearConstraint> > GetAllLinearConstraints ( ) const

Getter returning all linear constraints (both linear equality and inequality constraints).

Returns
Vector of all linear constraint bindings.

◆ GetInitialGuess() [1/2]

double GetInitialGuess ( const symbolic::Variable decision_variable) const

Gets the initial guess for a single variable.

Precondition
decision_variable has been registered in the optimization program.
Exceptions
std::runtime_errorif the pre condition is not satisfied.

◆ GetInitialGuess() [2/2]

std::enable_if< std::is_same<typename Derived::Scalar, symbolic::Variable>::value, Eigen::Matrix<double, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime> >::type GetInitialGuess ( const Eigen::MatrixBase< Derived > &  decision_variable_mat) const

Gets the initial guess for some variables.

Precondition
Each variable in decision_variable_mat has been registered in the optimization program.
Exceptions
std::runtime_errorif the pre condition is not satisfied.

◆ GetSolverOptionsDouble()

const std::unordered_map<std::string, double>& GetSolverOptionsDouble ( const SolverId solver_id) const

◆ GetSolverOptionsInt()

const std::unordered_map<std::string, int>& GetSolverOptionsInt ( const SolverId solver_id) const

◆ GetSolverOptionsStr()

const std::unordered_map<std::string, std::string>& GetSolverOptionsStr ( const SolverId solver_id) const

◆ indeterminate()

const symbolic::Variable& indeterminate ( int  i) const

Getter for the indeterminate with index i in the program.

◆ indeterminates()

const VectorXIndeterminate& indeterminates ( ) const

Getter for all indeterminates in the program.

◆ initial_guess()

const Eigen::VectorXd& initial_guess ( ) const

Getter for the initial guess.

◆ linear_complementarity_constraints()

const std::vector<Binding<LinearComplementarityConstraint> >& linear_complementarity_constraints ( ) const

Getter for all linear complementarity constraints.

◆ linear_constraints()

const std::vector<Binding<LinearConstraint> >& linear_constraints ( ) const

Getter for linear constraints.

◆ linear_costs()

const std::vector<Binding<LinearCost> >& linear_costs ( ) const

Getter for linear costs.

◆ linear_equality_constraints()

const std::vector<Binding<LinearEqualityConstraint> >& linear_equality_constraints ( ) const

Getter for linear equality constraints.

◆ linear_matrix_inequality_constraints()

const std::vector<Binding<LinearMatrixInequalityConstraint> >& linear_matrix_inequality_constraints ( ) const

Getter for linear matrix inequality constraints.

◆ lorentz_cone_constraints()

const std::vector<Binding<LorentzConeConstraint> >& lorentz_cone_constraints ( ) const

Getter for Lorentz cone constraints.

◆ MakeCost()

static std::shared_ptr<Cost> MakeCost ( F &&  f)
static

Convert an input of type F to a FunctionCost object.

Template Parameters
FThis class should have functions numInputs(), numOutputs and eval(x, y).

◆ NewBinaryVariables() [1/3]

MatrixDecisionVariable<Rows, Cols> NewBinaryVariables ( int  rows,
int  cols,
const std::string &  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().

Template Parameters
RowsThe number of rows in the new variables.
ColsThe number of columns in the new variables.
Parameters
rowsThe number of rows in the new variables.
colsThe number of columns in the new variables.
nameThe commonly shared name of the new variables.
Returns
The MatrixDecisionVariable of size rows x cols, containing the new vars (not all the vars stored).

Example:

auto b = prog.NewBinaryVariables(2, 3, "b");

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.

◆ NewBinaryVariables() [2/3]

MatrixDecisionVariable<Rows, Cols> NewBinaryVariables ( const std::string &  name = "b")

Adds a matrix of binary variables into the optimization program.

Template Parameters
RowsThe number of rows in the newly added binary variables.
ColsThe number of columns in the new variables. The default is 1.
Parameters
nameEach newly added binary variable will share the same name. The default name is "b".
Returns
A matrix containing the newly added variables.

◆ NewBinaryVariables() [3/3]

VectorXDecisionVariable NewBinaryVariables ( int  rows,
const std::string &  name = "b" 
)

Adds binary variables to this MathematicalProgram.

The new variables are viewed as a column vector, with size rows x 1.

See also
NewBinaryVariables(int rows, int cols, const std::vector<std::string>& names);

◆ NewContinuousVariables() [1/3]

VectorXDecisionVariable NewContinuousVariables ( int  rows,
const std::string &  name = "x" 
)

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().

Parameters
rowsThe number of rows in the new variables.
nameThe name of the newly added variables
Returns
The VectorDecisionVariable of size rows x 1, containing the new vars (not all the vars stored).

Example:

auto x = prog.NewContinuousVariables(2, "x");

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.

◆ NewContinuousVariables() [2/3]

MatrixDecisionVariable<Rows, Cols> NewContinuousVariables ( int  rows,
int  cols,
const std::string &  name = "X" 
)

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().

Template Parameters
RowsThe number of rows of the new variables, in the compile time.
ColsThe number of columns of the new variables, in the compile time.
Parameters
rowsThe number of rows in the new variables. When Rows is not Eigen::Dynamic, rows is ignored.
colsThe number of columns in the new variables. When Cols is not Eigen::Dynamic, cols is ignored.
nameAll variables will share the same name, but different index.
Returns
The MatrixDecisionVariable of size Rows x Cols, containing the new vars (not all the vars stored).

Example:

auto x = prog.NewContinuousVariables(2, 3, "X");
auto y = prog.NewContinuousVariables<2, 3>(2, 3, "X");

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.

◆ NewContinuousVariables() [3/3]

MatrixDecisionVariable<Rows, Cols> NewContinuousVariables ( const std::string &  name = "X")

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().

Template Parameters
RowsThe number of rows in the new variables.
ColsThe number of columns in the new variables. The default is 1.
Parameters
nameAll variables will share the same name, but different index.
Returns
The MatrixDecisionVariable of size rows x cols, containing the new vars (not all the vars stored).

Example:

auto x = prog.NewContinuousVariables<2, 3>("X");

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.

◆ NewFreePolynomial()

symbolic::Polynomial NewFreePolynomial ( const symbolic::Variables indeterminates,
int  degree,
const std::string &  coeff_name = "a" 
)

Returns a free polynomial in a monomial basis over indeterminates of a given degree.

It uses 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₅.

◆ NewIndeterminates() [1/8]

MatrixIndeterminate<rows, cols> NewIndeterminates ( const std::array< std::string, rows *cols > &  names)

Adds indeterminates, appending them to an internal vector of any existing indeterminates.

Template Parameters
rowsThe number of rows in the new indeterminates.
colsThe number of columns in the new indeterminates.
Parameters
namesA vector of strings containing the name for each variable.
Returns
The MatrixIndeterminate of size rows x cols, containing the new vars (not all the vars stored).

Example:

std::array<std::string, 6> names = {"x1", "x2", "x3", "x4", "x5", "x6"};
auto x = prog.NewIndeterminates<2, 3>(names);

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.

◆ NewIndeterminates() [2/8]

VectorIndeterminate<rows> NewIndeterminates ( const std::array< std::string, rows > &  names)

Adds indeterminates, appending them to an internal vector of any existing indeterminates.

Template Parameters
rowsThe number of rows in the new indeterminates.
colsThe number of columns in the new indeterminates.
Parameters
namesA vector of strings containing the name for each variable.
Returns
The MatrixIndeterminate of size rows x cols, containing the new vars (not all the vars stored).

Example:

std::array<std::string, 2> names = {"x1", "x2"};
auto x = prog.NewIndeterminates<2>(names);

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.

◆ NewIndeterminates() [3/8]

MatrixIndeterminate<rows, cols> NewIndeterminates ( const std::string &  name = "X")

Adds indeterminates, appending them to an internal vector of any existing indeterminates.

Template Parameters
rowsThe number of rows in the new indeterminates.
colsThe number of columns in the new indeterminates.
Parameters
namesA vector of strings containing the name for each variable.
Returns
The MatrixIndeterminate of size rows x cols, containing the new vars (not all the vars stored).

Example:

auto x = prog.NewIndeterminates<2, 3>("X");

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.

◆ NewIndeterminates() [4/8]

VectorIndeterminate<rows> NewIndeterminates ( const std::string &  name = "x")

Adds indeterminates to the program.

The name for all newly added indeterminates are set to name. The default name is "x"

See also
NewIndeterminates(const std::array<std::string, rows>& names)

◆ NewIndeterminates() [5/8]

VectorXIndeterminate NewIndeterminates ( int  rows,
const std::vector< std::string > &  names 
)

Adds indeterminates to this MathematicalProgram.

See also
NewIndeterminates(int rows, int cols, const std::vector<std::string>& names);

◆ NewIndeterminates() [6/8]

VectorXIndeterminate NewIndeterminates ( int  rows,
const std::string &  name = "x" 
)

Adds indeterminates to this MathematicalProgram, with default name "x".

See also
NewIndeterminates(int rows, int cols, const std::vector<std::string>& names);

◆ NewIndeterminates() [7/8]

MatrixXIndeterminate NewIndeterminates ( int  rows,
int  cols,
const std::vector< std::string > &  names 
)

Adds indeterminates, appending them to an internal vector of any existing vars.

Parameters
rowsThe number of rows in the new indeterminates.
colsThe number of columns in the new indeterminates.
namesA vector of strings containing the name for each variable.
Returns
The MatrixIndeterminate of size rows x cols, containing the new vars (not all the vars stored).

Example:

auto x = prog.NewIndeterminates(2, 3, {"x1", "x2", "x3", "x4",
"x5", "x6"});

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.

◆ NewIndeterminates() [8/8]

MatrixXIndeterminate NewIndeterminates ( int  rows,
int  cols,
const std::string &  name = "X" 
)

Adds indeterminates to this MathematicalProgram, with default name "X".

The new variables are returned and viewed as a matrix, with size rows x cols.

See also
NewIndeterminates(int rows, int cols, const std::vector<std::string>& names);

◆ NewNonnegativePolynomial() [1/3]

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 Grammian matrix Q, where m is 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.
    Parameters
    monomial_basisThe monomial basis.
    typeThe type of the nonnegative polynomial.
    Returns
    (p, Q) The polynomial p and the Grammian matrix Q. Q has been added as decision variables to the program.

◆ NewNonnegativePolynomial() [2/3]

symbolic::Polynomial NewNonnegativePolynomial ( const Eigen::Ref< const MatrixX< symbolic::Variable >> &  grammian,
const Eigen::Ref< const VectorX< symbolic::Monomial >> &  monomial_basis,
NonnegativePolynomial  type 
)

Overloads NewNonnegativePolynomial(), except the Grammian matrix Q is an input instead of an output.

◆ NewNonnegativePolynomial() [3/3]

pair< symbolic::Polynomial, MatrixXDecisionVariable > NewNonnegativePolynomial ( const symbolic::Variables indeterminates,
int  degree,
NonnegativePolynomial  type 
)

Overloads NewNonnegativePolynomial().

Instead of passing the monomial basis, we use a monomial basis that contains all monomials of indeterminates of total order up to degree / 2, hence the returned polynomial p contains all the monomials of indeterminates of total order up to degree.

Parameters
indeterminatesAll the indeterminates in the polynomial p.
degreeThe polynomial p will contain all the monomials up to order degree.
typeThe type of the nonnegative polynomial.
Returns
(p, Q) The polynomial p and the Grammian matrix Q. Q has been added as decision variables to the program.
Precondition
degree is a positive even number.

◆ NewSosPolynomial() [1/2]

std::pair< symbolic::Polynomial, MatrixXDecisionVariable > NewSosPolynomial ( const Eigen::Ref< const VectorX< symbolic::Monomial >> &  monomial_basis)

Returns a pair of a SOS polynomial p = mᵀQm and the Grammian matrix Q, where m is the 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.

◆ NewSosPolynomial() [2/2]

pair< symbolic::Polynomial, MatrixXDecisionVariable > NewSosPolynomial ( const symbolic::Variables indeterminates,
int  degree 
)

Returns a pair of a SOS polynomial p = m(x)ᵀQm(x) of degree degree and the Grammian 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.

Exceptions
std::runtime_errorif degree is not a positive even integer.
See also
MonomialBasis.

◆ NewSymmetricContinuousVariables() [1/2]

MatrixXDecisionVariable NewSymmetricContinuousVariables ( int  rows,
const std::string &  name = "Symmetric" 
)

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.

Parameters
rowsThe number of rows in the symmetric matrix.
nameThe 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
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)
Notice that the (i,j)'th entry and (j,i)'th entry has the same name.
Returns
The newly added decision variables.

◆ NewSymmetricContinuousVariables() [2/2]

MatrixDecisionVariable<rows, rows> NewSymmetricContinuousVariables ( 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.

Template Parameters
rowsThe number of rows in the symmetric matrix.
Parameters
nameThe 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
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)
Notice that the (i,j)'th entry and (j,i)'th entry has the same name.
Returns
The newly added decision variables.

◆ num_indeterminates()

int num_indeterminates ( ) const

Gets the number of indeterminates in the optimization program.

◆ num_vars()

int num_vars ( ) const

Getter for number of variables in the optimization program.

◆ operator=() [1/2]

MathematicalProgram& operator= ( MathematicalProgram &&  )
delete

◆ operator=() [2/2]

MathematicalProgram& operator= ( const MathematicalProgram )
delete

◆ positive_semidefinite_constraints()

const std::vector<Binding<PositiveSemidefiniteConstraint> >& positive_semidefinite_constraints ( ) const

Getter for positive semidefinite constraints.

◆ quadratic_costs()

const std::vector<Binding<QuadraticCost> >& quadratic_costs ( ) const

Getter for quadratic costs.

◆ required_capabilities()

const ProgramAttributes& required_capabilities ( ) const

Getter for the required capability on the solver, given the cost/constraint/variable types in the program.

◆ rotated_lorentz_cone_constraints()

const std::vector<Binding<RotatedLorentzConeConstraint> >& rotated_lorentz_cone_constraints ( ) const

Getter for rotated Lorentz cone constraints.

◆ SetDecisionVariableValueInVector() [1/2]

void SetDecisionVariableValueInVector ( const symbolic::Variable decision_variable,
double  decision_variable_new_value,
EigenPtr< Eigen::VectorXd >  values 
) const

Updates the value of a single decision_variable inside the values vector to be decision_variable_new_value.

The other decision variables' values in values are unchanged.

Parameters
decision_variablea registered decision variable in this program.
decision_variable_new_valuethe variable's new values.
[in,out]valuesThe vector to be tweaked; must be of size num_vars().

◆ SetDecisionVariableValueInVector() [2/2]

void SetDecisionVariableValueInVector ( const Eigen::Ref< const MatrixXDecisionVariable > &  decision_variables,
const Eigen::Ref< const Eigen::MatrixXd > &  decision_variables_new_values,
EigenPtr< Eigen::VectorXd >  values 
) const

Updates the values of some decision_variables inside the values vector to be decision_variables_new_values.

The other decision variables' values in values are unchanged.

Parameters
decision_variablesregistered decision variables in this program.
decision_variables_new_valuesthe variables' respective new values; must have the same rows() and cols() sizes and decision_variables.
[in,out]valuesThe vector to be tweaked; must be of size num_vars().

◆ SetInitialGuess() [1/2]

void SetInitialGuess ( const symbolic::Variable decision_variable,
double  variable_guess_value 
)

Sets the initial guess for a single variable decision_variable.

The guess is stored as part of this program.

Precondition
decision_variable is a registered decision variable in the program.
Exceptions
std::runtime_errorif precondition is not satisfied.

◆ SetInitialGuess() [2/2]

void SetInitialGuess ( const Eigen::MatrixBase< DerivedA > &  decision_variable_mat,
const Eigen::MatrixBase< DerivedB > &  x0 
)

Sets the initial guess for the decision variables stored in decision_variable_mat to be x0.

The guess is stored as part of this program.

◆ SetInitialGuessForAllVariables()

void SetInitialGuessForAllVariables ( const Eigen::MatrixBase< Derived > &  x0)

Set the initial guess for ALL decision variables.

Note that variables begin with a default initial guess of NaN to indicate that no guess is available.

Parameters
x0A vector of appropriate size (num_vars() x 1).

◆ SetSolverOption() [1/3]

void SetSolverOption ( const SolverId solver_id,
const std::string &  solver_option,
double  option_value 
)

◆ SetSolverOption() [2/3]

void SetSolverOption ( const SolverId solver_id,
const std::string &  solver_option,
int  option_value 
)

◆ SetSolverOption() [3/3]

void SetSolverOption ( const SolverId solver_id,
const std::string &  solver_option,
const std::string &  option_value 
)

◆ SetSolverOptions()

void SetSolverOptions ( const SolverOptions solver_options)

Overwrite the stored solver options inside MathematicalProgram with the provided solver options.

◆ solver_options()

const SolverOptions& solver_options ( ) const

Returns the solver options stored inside MathematicalProgram.

◆ visualization_callbacks()

const std::vector<Binding<VisualizationCallback> >& visualization_callbacks ( ) const

Getter for all callbacks.

Member Data Documentation

◆ kGlobalInfeasibleCost

constexpr double kGlobalInfeasibleCost
static
Initial value:
=
std::numeric_limits<double>::infinity()

The optimal cost is +∞ when the problem is globally infeasible.

◆ kUnboundedCost

constexpr double kUnboundedCost
static
Initial value:
=
-std::numeric_limits<double>::infinity()

The optimal cost is -∞ when the problem is unbounded.


The documentation for this class was generated from the following files: