Drake
Drake C++ Documentation
Polynomial Class Reference

Detailed Description

Represents symbolic polynomials.

A symbolic polynomial keeps a mapping from a monomial of indeterminates to its coefficient in a symbolic expression.

A polynomial p has to satisfy an invariant such that p.decision_variables() ∩ p.indeterminates() = ∅. We have CheckInvariant() method to check the invariant.

Operation between a Polynomial and a Variable

Note that for arithmetic operations ⊕ (where ⊕ can be +,-,*) between a Polynomial p and a Variable v, if the variable v is an indeterminate of the polynomial p, then we regard v as a monomial with indeterminate v with coefficient 1; on the other hand, if the variable v is not an indeterminate of p, then we regard v as a monomial with 0 degree and coefficient v, and v will be appended to decision_variables() of the resulted polynomial. For example, if p = ax²+y where (x,y) are indeterminates and a is a decision variable, then in the operation p + y, the result stores the monomial-to-coefficient mapping as {(x² -> a), (y -> 2)}; on the other hand, in the operation p + b, b is regarded as a 0-degree monomial with coefficient b, and p + b stores the monomial-to-coefficient mapping as {(x² -> a), (y -> 1), (1 -> b)}, with (p + b).decision_variables() being {a, b}. If you want to append the variable v to the indeterminates of the p⊕v, then explicitly convert it to a monomial as p ⊕ symbolic::Monomial(v).

#include <drake/common/symbolic/polynomial.h>

Classes

struct  SubstituteAndExpandCacheData
 An encapsulated data type for use with the method SubstituteAndExpand. More...
 

Public Types

using MapType = std::map< Monomial, Expression, internal::CompareMonomial >
 

Public Member Functions

 Polynomial ()=default
 Constructs a zero polynomial. More...
 
 Polynomial (std::nullptr_t)
 Constructs a default value. More...
 
 Polynomial (MapType map)
 Constructs a polynomial from a map, MonomialExpression. More...
 
 Polynomial (const Monomial &m)
 Constructs a polynomial from a monomial m. More...
 
 Polynomial (const Variable &v)
 Constructs a polynomial from a varaible v. More...
 
 Polynomial (const Expression &e)
 Constructs a polynomial from an expression e. More...
 
 Polynomial (const Expression &e, Variables indeterminates)
 Constructs a polynomial from an expression e by decomposing it with respect to indeterminates. More...
 
const Variablesindeterminates () const
 Returns the indeterminates of this polynomial. More...
 
const Variablesdecision_variables () const
 Returns the decision variables of this polynomial. More...
 
void SetIndeterminates (const Variables &new_indeterminates)
 Sets the indeterminates to new_indeterminates. More...
 
int Degree (const Variable &v) const
 Returns the highest degree of this polynomial in a variable v. More...
 
int TotalDegree () const
 Returns the total degree of this polynomial. More...
 
const MapTypemonomial_to_coefficient_map () const
 Returns the mapping from a Monomial to its corresponding coefficient of this polynomial. More...
 
Expression ToExpression () const
 Returns an equivalent symbolic expression of this polynomial. More...
 
Polynomial Differentiate (const Variable &x) const
 Differentiates this polynomial with respect to the variable x. More...
 
template<typename Derived >
Eigen::Matrix< Polynomial, 1, Derived::RowsAtCompileTime > Jacobian (const Eigen::MatrixBase< Derived > &vars) const
 Computes the Jacobian matrix J of the polynomial with respect to vars. More...
 
Polynomial Integrate (const Variable &x) const
 Integrates this polynomial with respect to an indeterminate x. More...
 
Polynomial Integrate (const Variable &x, double a, double b) const
 Computes the definite integrate of this polynomial with respect to the indeterminate x over the domain [a, b]. More...
 
double Evaluate (const Environment &env) const
 Evaluates this polynomial under a given environment env. More...
 
Polynomial EvaluatePartial (const Environment &env) const
 Partially evaluates this polynomial using an environment env. More...
 
Polynomial EvaluatePartial (const Variable &var, double c) const
 Partially evaluates this polynomial by substituting var with c. More...
 
Eigen::VectorXd EvaluateIndeterminates (const Eigen::Ref< const VectorX< symbolic::Variable >> &indeterminates, const Eigen::Ref< const Eigen::MatrixXd > &indeterminates_values) const
 Evaluates the polynomial at a batch of indeterminates values. More...
 
void EvaluateWithAffineCoefficients (const Eigen::Ref< const VectorX< symbolic::Variable >> &indeterminates, const Eigen::Ref< const Eigen::MatrixXd > &indeterminates_values, Eigen::MatrixXd *A, VectorX< symbolic::Variable > *decision_variables, Eigen::VectorXd *b) const
 Evaluates the polynomial at a batch of indeterminate values. More...
 
PolynomialAddProduct (const Expression &coeff, const Monomial &m)
 Adds coeff * m to this polynomial. More...
 
Polynomial SubstituteAndExpand (const std::unordered_map< Variable, Polynomial > &indeterminate_substitution, SubstituteAndExpandCacheData *substitutions_cached_data=nullptr) const
 Substitutes the monomials of this polynomial with new polynomial expressions and expand the polynomial to the monomial basis. More...
 
Polynomial Expand () const
 Expands each coefficient expression and returns the expanded polynomial. More...
 
Polynomial RemoveTermsWithSmallCoefficients (double coefficient_tol) const
 Removes the terms whose absolute value of the coefficients are smaller than or equal to coefficient_tol. More...
 
bool IsEven () const
 Returns true if the polynomial is even, namely p(x) = p(-x). More...
 
bool IsOdd () const
 Returns true if the polynomial is odd, namely p(x) = -p(-x). More...
 
Eigen::VectorXcd Roots () const
 Returns the roots of a univariate polynomial with constant coefficients as a column vector. More...
 
Polynomialoperator+= (const Polynomial &p)
 
Polynomialoperator+= (const Monomial &m)
 
Polynomialoperator+= (double c)
 
Polynomialoperator+= (const Variable &v)
 Depending on whether v is an indeterminate of this polynomial, this operation generates different results. More...
 
Polynomialoperator-= (const Polynomial &p)
 
Polynomialoperator-= (const Monomial &m)
 
Polynomialoperator-= (double c)
 
Polynomialoperator-= (const Variable &v)
 Depending on whether v is an indeterminate of this polynomial, this operation generates different results. More...
 
Polynomialoperator *= (const Polynomial &p)
 
Polynomialoperator *= (const Monomial &m)
 
Polynomialoperator *= (double c)
 
Polynomialoperator *= (const Variable &v)
 Depending on whether v is an indeterminate of this polynomial, this operation generates different results. More...
 
bool EqualTo (const Polynomial &p) const
 Returns true if this polynomial and p are structurally equal. More...
 
bool CoefficientsAlmostEqual (const Polynomial &p, double tolerance) const
 Returns true if this polynomial and p are almost equal (the difference in the corresponding coefficients are all less than tolerance), after expanding the coefficients. More...
 
Formula operator== (const Polynomial &p) const
 Returns a symbolic formula representing the condition where this polynomial and p are the same. More...
 
Formula operator!= (const Polynomial &p) const
 Returns a symbolic formula representing the condition where this polynomial and p are not the same. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 Polynomial (const Polynomial &)=default
 
Polynomialoperator= (const Polynomial &)=default
 
 Polynomial (Polynomial &&)=default
 
Polynomialoperator= (Polynomial &&)=default
 

Friends

template<class HashAlgorithm >
void hash_append (HashAlgorithm &hasher, const Polynomial &item) noexcept
 Implements the hash_append generic hashing concept. More...
 
Polynomial operator/ (Polynomial p, double v)
 Returns p / v. More...
 

Member Typedef Documentation

◆ MapType

using MapType = std::map<Monomial, Expression, internal::CompareMonomial>

Constructor & Destructor Documentation

◆ Polynomial() [1/9]

Polynomial ( )
default

Constructs a zero polynomial.

◆ Polynomial() [2/9]

Polynomial ( const Polynomial )
default

◆ Polynomial() [3/9]

Polynomial ( Polynomial &&  )
default

◆ Polynomial() [4/9]

Polynomial ( std::nullptr_t  )
explicit

Constructs a default value.

This overload is used by Eigen when EIGEN_INITIALIZE_MATRICES_BY_ZERO is enabled.

◆ Polynomial() [5/9]

Polynomial ( MapType  map)
explicit

Constructs a polynomial from a map, MonomialExpression.

◆ Polynomial() [6/9]

Polynomial ( const Monomial m)

Constructs a polynomial from a monomial m.

Note that all variables in m are considered as indeterminates. Note that this implicit conversion is desirable to have a dot product of two Eigen::Vector<Monomial>s return a Polynomial.

◆ Polynomial() [7/9]

Polynomial ( const Variable v)
explicit

Constructs a polynomial from a varaible v.

Note that v is considered an indeterminate.

◆ Polynomial() [8/9]

Polynomial ( const Expression e)
explicit

Constructs a polynomial from an expression e.

Note that all variables in e are considered as indeterminates.

Exceptions
std::exceptionif e is not a polynomial.

◆ Polynomial() [9/9]

Polynomial ( const Expression e,
Variables  indeterminates 
)

Constructs a polynomial from an expression e by decomposing it with respect to indeterminates.

Note
It collects the intersection of the variables appeared in e and the provided indeterminates.
Exceptions
std::exceptionif e is not a polynomial in indeterminates.

Member Function Documentation

◆ AddProduct()

Polynomial& AddProduct ( const Expression coeff,
const Monomial m 
)

Adds coeff * m to this polynomial.

◆ CoefficientsAlmostEqual()

bool CoefficientsAlmostEqual ( const Polynomial p,
double  tolerance 
) const

Returns true if this polynomial and p are almost equal (the difference in the corresponding coefficients are all less than tolerance), after expanding the coefficients.

◆ decision_variables()

const Variables& decision_variables ( ) const

Returns the decision variables of this polynomial.

◆ Degree()

int Degree ( const Variable v) const

Returns the highest degree of this polynomial in a variable v.

◆ Differentiate()

Polynomial Differentiate ( const Variable x) const

Differentiates this polynomial with respect to the variable x.

Note that a variable x can be either a decision variable or an indeterminate.

◆ EqualTo()

bool EqualTo ( const Polynomial p) const

Returns true if this polynomial and p are structurally equal.

◆ Evaluate()

double Evaluate ( const Environment env) const

Evaluates this polynomial under a given environment env.

Exceptions
std::exceptionif there is a variable in this polynomial whose assignment is not provided by env.

◆ EvaluateIndeterminates()

Eigen::VectorXd EvaluateIndeterminates ( const Eigen::Ref< const VectorX< symbolic::Variable >> &  indeterminates,
const Eigen::Ref< const Eigen::MatrixXd > &  indeterminates_values 
) const

Evaluates the polynomial at a batch of indeterminates values.

Parameters
[in]indeterminatesMust include all this->indeterminates()
[in]indeterminates_valuesEach column of indeterminates_values stores one specific value of indeterminates; indeterminates_values.rows() == indeterminates.rows().
Returns
polynomial_values polynomial_values(j) is obtained by substituting indeterminates(i) in this polynomial with indeterminates_values(i, j) for all i.
Exceptions
std::exceptionif any coefficient in this polynomial is not a constant.

◆ EvaluatePartial() [1/2]

Polynomial EvaluatePartial ( const Environment env) const

Partially evaluates this polynomial using an environment env.

Exceptions
std::exceptionif NaN is detected during evaluation.

◆ EvaluatePartial() [2/2]

Polynomial EvaluatePartial ( const Variable var,
double  c 
) const

Partially evaluates this polynomial by substituting var with c.

Exceptions
std::exceptionif NaN is detected at any point during evaluation.

◆ EvaluateWithAffineCoefficients()

void EvaluateWithAffineCoefficients ( const Eigen::Ref< const VectorX< symbolic::Variable >> &  indeterminates,
const Eigen::Ref< const Eigen::MatrixXd > &  indeterminates_values,
Eigen::MatrixXd *  A,
VectorX< symbolic::Variable > *  decision_variables,
Eigen::VectorXd *  b 
) const

Evaluates the polynomial at a batch of indeterminate values.

For a polynomial whose coefficients are affine expressions of decision variables, we evaluate this polynomial on a batch of indeterminate values, and return the matrix representation of the evaluated affine expressions. For example if p(x) = (a+1)x² + b*x where a, b are decision variables, if we evaluate this polynomial on x = 1 and x = 2, then p(x) = a+b+1 and 4a+2b+4 respectively. We return the evaluation result as A * decision_variables + b, where A.row(i) * decision_variables + b(i) is the evaluation of the polynomial on indeterminates_values.col(i).

Parameters
[in]indeterminatesMust include all this->indeterminates()
[in]indeterminates_valuesA matrix representing a batch of values. Each column of indeterminates_values stores one specific value of indeterminates, where indeterminates_values.rows() == indeterminates.rows().
[out]AThe coefficient of the evaluation results.
[out]decision_variablesThe decision variables in the evaluation results.
[out]bThe constant terms in the evaluation results.
Exceptions
std::exceptionif the coefficients of this polynomial is not an affine expression of its decision variables. For example, the polynomial (2+sin(a)) * x² + 1 (where a is a decision variable and x is a indeterminate) doesn't have affine expression as its coefficient 2+sin(a).

◆ Expand()

Polynomial Expand ( ) const

Expands each coefficient expression and returns the expanded polynomial.

If any coefficient is equal to 0 after expansion, then remove that term from the returned polynomial.

◆ indeterminates()

const Variables& indeterminates ( ) const

Returns the indeterminates of this polynomial.

◆ Integrate() [1/2]

Polynomial Integrate ( const Variable x) const

Integrates this polynomial with respect to an indeterminate x.

Integration with respect to decision variables is not supported yet. If x is not an indeterminate nor decision variable, then it will be added to the list of indeterminates.

Exceptions
std::exceptionif x is a decision variable.

◆ Integrate() [2/2]

Polynomial Integrate ( const Variable x,
double  a,
double  b 
) const

Computes the definite integrate of this polynomial with respect to the indeterminate x over the domain [a, b].

Integration with respect to decision variables is not supported yet.

Exceptions
std::exceptionif x is a decision variable.

◆ IsEven()

bool IsEven ( ) const

Returns true if the polynomial is even, namely p(x) = p(-x).

Meaning that the coefficient for all odd-degree monomials are 0. Returns false otherwise. Note that this is different from the p.TotalDegree() being an even number.

◆ IsOdd()

bool IsOdd ( ) const

Returns true if the polynomial is odd, namely p(x) = -p(-x).

Meaning that the coefficient for all even-degree monomials are 0. Returns false otherwise. Note that this is different from the p.TotalDegree() being an odd number.

◆ Jacobian()

Eigen::Matrix<Polynomial, 1, Derived::RowsAtCompileTime> Jacobian ( const Eigen::MatrixBase< Derived > &  vars) const

Computes the Jacobian matrix J of the polynomial with respect to vars.

J(0,i) contains ∂f/∂vars(i).

◆ monomial_to_coefficient_map()

const MapType& monomial_to_coefficient_map ( ) const

Returns the mapping from a Monomial to its corresponding coefficient of this polynomial.

We maintain the invariance that for any [monomial, coeff] pair in monomial_to_coefficient_map(), symbolic:is_zero(coeff) is false.

◆ operator *=() [1/4]

Polynomial& operator *= ( const Polynomial p)

◆ operator *=() [2/4]

Polynomial& operator *= ( const Monomial m)

◆ operator *=() [3/4]

Polynomial& operator *= ( double  c)

◆ operator *=() [4/4]

Polynomial& operator *= ( const Variable v)

Depending on whether v is an indeterminate of this polynomial, this operation generates different results.

Refer to the class documentation for more details.

◆ operator!=()

Formula operator!= ( const Polynomial p) const

Returns a symbolic formula representing the condition where this polynomial and p are not the same.

◆ operator+=() [1/4]

Polynomial& operator+= ( const Polynomial p)

◆ operator+=() [2/4]

Polynomial& operator+= ( const Monomial m)

◆ operator+=() [3/4]

Polynomial& operator+= ( double  c)

◆ operator+=() [4/4]

Polynomial& operator+= ( const Variable v)

Depending on whether v is an indeterminate of this polynomial, this operation generates different results.

Refer to the class documentation for more details.

◆ operator-=() [1/4]

Polynomial& operator-= ( const Polynomial p)

◆ operator-=() [2/4]

Polynomial& operator-= ( const Monomial m)

◆ operator-=() [3/4]

Polynomial& operator-= ( double  c)

◆ operator-=() [4/4]

Polynomial& operator-= ( const Variable v)

Depending on whether v is an indeterminate of this polynomial, this operation generates different results.

Refer to the class documentation for more details.

◆ operator=() [1/2]

Polynomial& operator= ( Polynomial &&  )
default

◆ operator=() [2/2]

Polynomial& operator= ( const Polynomial )
default

◆ operator==()

Formula operator== ( const Polynomial p) const

Returns a symbolic formula representing the condition where this polynomial and p are the same.

◆ RemoveTermsWithSmallCoefficients()

Polynomial RemoveTermsWithSmallCoefficients ( double  coefficient_tol) const

Removes the terms whose absolute value of the coefficients are smaller than or equal to coefficient_tol.

For example, if the polynomial is 2x² + 3xy + 10⁻⁴x - 10⁻⁵, then after calling RemoveTermsWithSmallCoefficients(1e-3), the returned polynomial becomes 2x² + 3xy.

Parameters
coefficient_tolA positive scalar.
Return values
polynomial_cleanedA polynomial whose terms with small coefficients are removed.

◆ Roots()

Eigen::VectorXcd Roots ( ) const

Returns the roots of a univariate polynomial with constant coefficients as a column vector.

There is no specific guarantee on the order of the returned roots.

Exceptions
std::exceptionif this is not univariate with constant coefficients.

◆ SetIndeterminates()

void SetIndeterminates ( const Variables new_indeterminates)

Sets the indeterminates to new_indeterminates.

Changing the indeterminates would change monomial_to_coefficient_map(), and also potentially the degree of the polynomial. Here is an example.

// p is a quadratic polynomial with x being the indeterminates.
symbolic::Polynomial p(a * x * x + b * x + c, {x});
// p.monomial_to_coefficient_map() contains {1: c, x: b, x*x:a}.
std::cout << p.TotalDegree(); // prints 2.
// Now set (a, b, c) to the indeterminates. p becomes a linear
// polynomial of a, b, c.
p.SetIndeterminates({a, b, c});
// p.monomial_to_coefficient_map() now is {a: x * x, b: x, c: 1}.
std::cout << p.TotalDegree(); // prints 1.

◆ SubstituteAndExpand()

Polynomial SubstituteAndExpand ( const std::unordered_map< Variable, Polynomial > &  indeterminate_substitution,
SubstituteAndExpandCacheData substitutions_cached_data = nullptr 
) const

Substitutes the monomials of this polynomial with new polynomial expressions and expand the polynomial to the monomial basis.

For example, consider the substitution x = a(1-y) into the polynomial x¹⁴ + (x−1)². Repeatedly expanding the powers of x can take a long time using factory methods, so we store intermediate computations in the substitution map to avoid recomputing very high powers.

Parameters
indeterminate_substitutionThe substitutions of every indeterminate with the new desired expression. This map must contain each element of indeterminates(). For performance reasons, it is recommended that this map contains Expanded polynomials as its values, but this is not necessary.
[in,out]substitutions_cached_dataA container caching the higher order expansions of the indeterminate_substitutions. Typically, the first time an indeterminate_substitution is performed, this will be empty. If the same indeterminate_substitutions is used for multiple polynomials, passing this value will enable the user to re-use the expansions across multiple calls. For example, suppose we wish to perform the substitution x = a(1-y) into the polynomials p1 = x¹⁴ + (x−1)² and p2 = x⁷. A user may call p1.SubstituteAndExpand({x : a(1-y), substitutions_cached_data}) where substitutions_cached_data is a pointer to an empty container. As part of computing the expansion of p1, the expansion of x⁷ may get computed and stored in substitutions_cached_data, and so a subsequent call of p2.SubstituteAndExpand({x : a(1-y)}, substitutions_cached_data) would be very fast.

Never reuse substitutions_cached_data if indeterminate_substitutions changes as this function will then compute an incorrect result.

Note that this function is NOT responsible for ensuring that substitutions_cached_data is consistent i.e. this method will not throw an error if substitutions_cached_data contains the inconsistent substitutions {x: y, x²: 2y}. To ensure correct results, ensure that the passed substitutions_cached_data object is consistent with indeterminate_substitutions. The easiest way to do this is to pass a pointer to an empty substitutions_cached_data or nullopt to this function.

◆ ToExpression()

Expression ToExpression ( ) const

Returns an equivalent symbolic expression of this polynomial.

◆ TotalDegree()

int TotalDegree ( ) const

Returns the total degree of this polynomial.

Friends And Related Function Documentation

◆ hash_append

void hash_append ( HashAlgorithm &  hasher,
const Polynomial item 
)
friend

Implements the hash_append generic hashing concept.

◆ operator/

Polynomial operator/ ( Polynomial  p,
double  v 
)
friend

Returns p / v.


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