Drake
Polynomial Class Reference

Represents symbolic polynomials. More...

#include <drake/common/symbolic_polynomial.h>

Public Types

using MapType = std::unordered_map< Monomial, Expression >
 

Public Member Functions

 Polynomial ()=default
 Constructs a zero polynomial. More...
 
 Polynomial (std::nullptr_t)
 Constructs a default value. More...
 
 Polynomial (MapType init)
 Constructs a polynomial from a map, MonomialExpression. More...
 
 Polynomial (const Monomial &m)
 Constructs a polynomial from a monomial m. More...
 
 Polynomial (const Expression &e)
 Constructs a polynomial from an expression e. More...
 
 Polynomial (const Expression &e, const Variables &indeterminates)
 Constructs a polynomial from an expression e by decomposing it with respect to indeterminates. More...
 
Variables indeterminates () const
 Returns the indeterminates of this polynomial. More...
 
Variables decision_variables () const
 Returns the decision variables of this polynomial. 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...
 
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...
 
PolynomialAddProduct (const Expression &coeff, const Monomial &m)
 Adds coeff * m to this 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 For example, if the polynomial is 2x² + 3xy + 10⁻⁴x - 10⁻⁵, then after calling RemoveTermsWithSmallCoefficients(1e-3), the returned polynomial becomes 2x² + 3xy. More...
 
Polynomialoperator+= (const Polynomial &p)
 
Polynomialoperator+= (const Monomial &m)
 
Polynomialoperator+= (double c)
 
Polynomialoperator-= (const Polynomial &p)
 
Polynomialoperator-= (const Monomial &m)
 
Polynomialoperator-= (double c)
 
Polynomialoperator*= (const Polynomial &p)
 
Polynomialoperator*= (const Monomial &m)
 
Polynomialoperator*= (double c)
 
bool EqualTo (const Polynomial &p) const
 Returns true if this polynomial and p are structurally equal. 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...
 

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.

Note that arithmetic operations (+,-,*) between a Polynomial and a Variable are not provided. The problem is that Variable class has no intrinsic information if a variable is a decision variable or an indeterminate while we need this information to perform arithmetic operations over Polynomials.

Member Typedef Documentation

using MapType = std::unordered_map<Monomial, Expression>

Constructor & Destructor Documentation

Polynomial ( )
default

Constructs a zero polynomial.

Polynomial ( const Polynomial )
default
Polynomial ( Polynomial &&  )
default
Polynomial ( std::nullptr_t  )
inlineexplicit

Constructs a default value.

This overload is used by Eigen when EIGEN_INITIALIZE_MATRICES_BY_ZERO is enabled.

Polynomial ( MapType  init)
explicit

Constructs a polynomial from a map, MonomialExpression.

Polynomial ( const Monomial m)

Constructs a polynomial from a monomial m.

Note that all variables in m are considered as indeterminates.

Polynomial ( const Expression e)
explicit

Constructs a polynomial from an expression e.

Note that all variables in e are considered as indeterminates.

Exceptions
std::runtime_errorif e is not a polynomial.
Polynomial ( const Expression e,
const 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::runtime_errorif e is not a polynomial in indeterminates.

Member Function Documentation

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

Adds coeff * m to this polynomial.

Variables decision_variables ( ) const

Returns the decision variables of this polynomial.

int Degree ( const Variable v) const

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

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.

bool EqualTo ( const Polynomial p) const

Returns true if this polynomial and p are structurally equal.

double Evaluate ( const Environment env) const

Evaluates this polynomial under a given environment env.

Exceptions
std::out_of_rangeif there is a variable in this polynomial whose assignment is not provided by env.
Polynomial EvaluatePartial ( const Environment env) const

Partially evaluates this polynomial using an environment env.

Exceptions
std::runtime_errorif NaN is detected during evaluation.
Polynomial EvaluatePartial ( const Variable var,
double  c 
) const

Partially evaluates this polynomial by substituting var with c.

Exceptions
std::runtime_errorif NaN is detected at any point during evaluation.
Variables indeterminates ( ) const

Returns the indeterminates of this polynomial.

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

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

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

const Polynomial::MapType & monomial_to_coefficient_map ( ) const

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

Formula operator!= ( const Polynomial p) const

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

Polynomial & operator*= ( const Polynomial p)
Polynomial & operator*= ( const Monomial m)
Polynomial & operator*= ( double  c)
Polynomial & operator+= ( const Polynomial p)
Polynomial & operator+= ( const Monomial m)
Polynomial & operator+= ( double  c)
Polynomial & operator-= ( const Polynomial p)
Polynomial & operator-= ( const Monomial m)
Polynomial & operator-= ( double  c)
Polynomial& operator= ( const Polynomial )
default
Polynomial& operator= ( Polynomial &&  )
default
Formula operator== ( const Polynomial p) const

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

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.
Expression ToExpression ( ) const

Returns an equivalent symbolic expression of this polynomial.

int TotalDegree ( ) const

Returns the total degree of this polynomial.

Friends And Related Function Documentation

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

Implements the hash_append generic hashing concept.


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