Public Types | Public Member Functions | List of all members
corbo::FiniteDifferencesInterface Class Referenceabstract

Interface class for finite difference approaches. More...

#include <finite_differences_interface.h>

Inheritance diagram for corbo::FiniteDifferencesInterface:
Inheritance graph
[legend]

Public Types

using InputVector = Eigen::VectorXd
 
using Ptr = std::shared_ptr< FiniteDifferencesInterface >
 
using StateVector = Eigen::VectorXd
 
using UPtr = std::unique_ptr< FiniteDifferencesInterface >
 

Public Member Functions

virtual void computeHessian (std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::Ref< Eigen::VectorXd >)> eval_fun, int dim_f, Eigen::Ref< Eigen::MatrixXd > hessian, const double *multipliers=nullptr)=0
 Compute Hessian of a desired function. More...
 
virtual void computeHessian2 (std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::VectorXd &)> eval_fun, int dim_f, Eigen::Ref< Eigen::MatrixXd > hessian, const double *multipliers=nullptr)=0
 Compute Hessian of a desired function (overload which accepts a slightly different callback function) More...
 
virtual void computeJacobian (std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::Ref< Eigen::VectorXd >)> eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian)=0
 Compute Jacobian of a desired function. More...
 
virtual void computeJacobian2 (std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::VectorXd &)> eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian)=0
 Compute Jacobian of a desired function (overload which accepts a slightly different callback function) More...
 
virtual void computeJacobianAndHessian (std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::Ref< Eigen::VectorXd >)> eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian, Eigen::Ref< Eigen::MatrixXd > hessian, const double *multipliers=nullptr)=0
 Compute Jacobian and Hessian of a desired function. More...
 
virtual void computeJacobianAndHessian2 (std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::VectorXd &)> eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian, Eigen::Ref< Eigen::MatrixXd > hessian, const double *multipliers=nullptr)=0
 Compute Jacobian and Hessian of a desired function (overload which accepts a slightly different callback function) More...
 
virtual FiniteDifferencesInterface::Ptr getInstance () const =0
 Return a newly allocated instances of the inherited class. More...
 
virtual ~FiniteDifferencesInterface ()
 Virtual destructor. More...
 

Detailed Description

Interface class for finite difference approaches.

This base class provides an interface for computing finite differences as derivative approximation for some relevant functions. For instance for computing the Jacobian matrices of the system dynamics function $ f(x, u) $f w.r.t. $ x $ and/or $ u $.

Remarks
This interface is provided with factory support (FiniteDifferencesFactory).
See also
ForwardDifferences CentralDifferences NumericalIntegratorExplicitInterface NumericalIntegratorExplicitInterface
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 60 of file finite_differences_interface.h.

Member Typedef Documentation

◆ InputVector

Definition at line 67 of file finite_differences_interface.h.

◆ Ptr

Definition at line 63 of file finite_differences_interface.h.

◆ StateVector

Definition at line 66 of file finite_differences_interface.h.

◆ UPtr

Definition at line 64 of file finite_differences_interface.h.

Constructor & Destructor Documentation

◆ ~FiniteDifferencesInterface()

virtual corbo::FiniteDifferencesInterface::~FiniteDifferencesInterface ( )
inlinevirtual

Virtual destructor.

Definition at line 70 of file finite_differences_interface.h.

Member Function Documentation

◆ computeHessian()

virtual void corbo::FiniteDifferencesInterface::computeHessian ( std::function< void(int, const double &)>  inc_fun,
std::function< void(Eigen::Ref< Eigen::VectorXd >)>  eval_fun,
int  dim_f,
Eigen::Ref< Eigen::MatrixXd >  hessian,
const double *  multipliers = nullptr 
)
pure virtual

Compute Hessian of a desired function.

Given a function $ f(x) $ with $ f: \mathbb{R}^p \to \mathbb{R}^n $. This method computes the $ n $ Hessian matrices of $ f(x) $ (element-wise) and accumulates them (optionally with individual scale factors). In case $ n=1 $, the Hessian is as follows:

\[ Hf_{1x}(x_0) = \begin{bmatrix} \partial^2_{x_1 x_1} f_1(x_0) & \partial^2_{x_1 x_2} f_1(x_0) & \cdots & \partial^2_{x_1 x_p} f_1(x_0) \\ \partial^2_{x_2 x_1} f_1(x_0) & \partial^2_{x_2 x_2} f_1(x_0) & \cdots & \partial^2_{x_2 x_p} f_1(x_0) \\ \vdots \\ \partial^2_{x_p x_1} f_1(x_0) & \partial^2_{x_p x_2} f_1(x_0) & \cdots & \partial^2_{x_p x_p} f_1(x_0) \end{bmatrix} \]

The Hessian is evaluated at $ x_0 $.

Function prototypes inc_fun and eval_fun are similar to computeJacobian(). In case the function callback is defined in terms of taking an Eigen::VectorXd& into account rather than Eigen::Ref<Eigen::VectorXd> refer to overload computeHessian2()

See also
computeHessian2 computeJacobianAndHessian
Parameters
[in]inc_funFunction callback to the increment operator function
[in]eval_funFunction callback to the function evaluation
[in]dim_fDimension of the function value vector (obtained from eval_fun)
[out]hessianThe resulting Hessian matrix (warning: hessian must be preallocated as p x p matrix)
[in]multipliers(optional) Vector of multipliers for scaling individual Hessian terms [dim_f x 1].

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.

◆ computeHessian2()

virtual void corbo::FiniteDifferencesInterface::computeHessian2 ( std::function< void(int, const double &)>  inc_fun,
std::function< void(Eigen::VectorXd &)>  eval_fun,
int  dim_f,
Eigen::Ref< Eigen::MatrixXd >  hessian,
const double *  multipliers = nullptr 
)
pure virtual

Compute Hessian of a desired function (overload which accepts a slightly different callback function)

Refer to the documentation of computeHessian(). This method takes type Eigen::VectorXd& into account for the function evaluation callback rather than Eigen::Ref<Eigen::VectorXd>.

See also
computeHessian computeJacobianAndHessian2
Parameters
[in]inc_funFunction callback to the increment operator function
[in]eval_funFunction callback to the function evaluation
[in]dim_fDimension of the function value vector (obtained from eval_fun)
[out]hessianThe resulting Hessian matrix (warning: hessian must be preallocated as p x p matrix)
[in]multipliers(optional) Vector of multipliers for scaling individual Hessian terms [dim_f x 1].

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.

◆ computeJacobian()

virtual void corbo::FiniteDifferencesInterface::computeJacobian ( std::function< void(int, const double &)>  inc_fun,
std::function< void(Eigen::Ref< Eigen::VectorXd >)>  eval_fun,
Eigen::Ref< Eigen::MatrixXd >  jacobian 
)
pure virtual

Compute Jacobian of a desired function.

Given a function $ f(x) $ with $ f: \mathbb{R}^p \to \mathbb{R}^n $. This method computes the Jacobian matrix

\[ Jf_x(x_0) = \begin{bmatrix} \partial_{x_1} f_1(x_0) & \partial_{x_2} f_1(x_0) & \cdots & \partial_{x_p} f_1(x_0) \\ \partial_{x_1} f_2(x_0) & \partial_{x_2} f_2(x_0) & \cdots & \partial_{x_p} f_2(x_0) \\ \vdots \\ \partial_{x_1} f_p(x_0) & \partial_{x_2} f_p(x_0) & \cdots & \partial_{x_p} f_p(x_0) \end{bmatrix} \]

The Jacobian is evaluated at $ x_0 $.

The function $ f $ is defined by a function of the following prototype:

void fun(Eigen::Ref<Eigen::VectorXd> values);

Hereby, fun should return the function values via output argument values as (n x 1) vector by implicitly taking the current working point $ x_0 $ into account. Note, you might want to bind other parameters to fun by using lambdas or std::bind().

Furthermore, a second function needs to be provided, in particular an implempation of the increment operator. Within Jacobian computation, the variable $ x $ needs to be varied (for computing finite differences). This can be achieved in a callback fashion by providing the increment function according to the following prototype:

void inc(int idx, const double& value);

Herebey, the first parameter determines which index (element in $ x $) needs to be incremented, and the second contains the actual increment value.

Example implementation:

Eigen::Vector2d x(1,1); // variable x initialized with [1, 1]^T as current working point (dimension p=2)
auto inc = [&x](int idx, const double& value){x[idx] += value;}; // define increment as simple x[idx]+=value, also bind x.
auto fun = [&x](Eigen::Ref<Eigen::VectorXd> values)
{
values[0] = x[0] * x[0] + 1; // f1 = x1^2 + 1
values[1] = x[1] * x[0] + 2; // f2 = x1*x2 + 2
}; // dimension n=2
Eigen::MatrixXd jacobian(2,2); // we must initialize/pre-allocate the jacobian with the correct size [p x n]
computeJacobian(inc, fun, jacobian);

In case the function callback is defined in terms of taking an Eigen::VectorXd& into account rather than Eigen::Ref<Eigen::VectorXd> refer to overload computeJacobian2()

See also
computeJacobian2 computeJacobianAndHessian
Parameters
[in]inc_funFunction callback to the increment operator function
[in]eval_funFunction callback to the function evaluation
[out]jacobianThe resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix)

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.

◆ computeJacobian2()

virtual void corbo::FiniteDifferencesInterface::computeJacobian2 ( std::function< void(int, const double &)>  inc_fun,
std::function< void(Eigen::VectorXd &)>  eval_fun,
Eigen::Ref< Eigen::MatrixXd >  jacobian 
)
pure virtual

Compute Jacobian of a desired function (overload which accepts a slightly different callback function)

Refer to the documentation of computeJacobian(). This method takes type Eigen::VectorXd& into account for the function evaluation callback rather than Eigen::Ref<Eigen::VectorXd>.

See also
computeJacobian computeJacobianAndHessian2
Parameters
[in]inc_funFunction callback to the increment operator function
[in]eval_funFunction callback to the function evaluation
[out]jacobianThe resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix)

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.

◆ computeJacobianAndHessian()

virtual void corbo::FiniteDifferencesInterface::computeJacobianAndHessian ( std::function< void(int, const double &)>  inc_fun,
std::function< void(Eigen::Ref< Eigen::VectorXd >)>  eval_fun,
Eigen::Ref< Eigen::MatrixXd >  jacobian,
Eigen::Ref< Eigen::MatrixXd >  hessian,
const double *  multipliers = nullptr 
)
pure virtual

Compute Jacobian and Hessian of a desired function.

This method is often faster than invoking computeJacobian() and computeHessian() separately.

Refer to the individual methods to obtain details regarding arguments and usage.

EvalFun should be of type void(Eigen::VectorXd& values) or similar and should return current function values. IncFun should be of type void(int idx, double value) and should increment component idx by value. The dimension of the function provided by eval_f is obtained by checking the number of allocated rows of the jacobian variable. In case dim_f > 1, the hessian is computed for each dimension and summed up. Optionally, individual hessians might be scaled by a multiplier which is common in solving nonlinear programs (e.g., Lagrangian). If provided, the multiplier vector should be of size [dim_f x 1].

Function prototypes inc_fun and eval_fun are similar to computeJacobian(). In case the function callback is defined in terms of taking an Eigen::VectorXd& into account rather than Eigen::Ref<Eigen::VectorXd> refer to overload computeJacobianAndHessian2()

Note
The Jacobian is also scaled by the multipliers if provided.
See also
computeJacobian computeHessian computeJacobianAndHessian2
Parameters
[in]inc_funFunction callback to the increment operator function
[in]eval_funFunction callback to the function evaluation
[out]jacobianThe resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix)
[out]hessianThe resulting Hessian matrix (warning: hessian must be preallocated as p x p matrix)
[in]multipliers(optional) Vector of multipliers for scaling individual Hessian terms [dim_f x 1].

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.

◆ computeJacobianAndHessian2()

virtual void corbo::FiniteDifferencesInterface::computeJacobianAndHessian2 ( std::function< void(int, const double &)>  inc_fun,
std::function< void(Eigen::VectorXd &)>  eval_fun,
Eigen::Ref< Eigen::MatrixXd >  jacobian,
Eigen::Ref< Eigen::MatrixXd >  hessian,
const double *  multipliers = nullptr 
)
pure virtual

Compute Jacobian and Hessian of a desired function (overload which accepts a slightly different callback function)

Refer to the documentation of computeJacobianAndHessian(). This method takes type Eigen::VectorXd& into account for the function evaluation callback rather than Eigen::Ref<Eigen::VectorXd>.

Note
The Jacobian is also scaled by the multipliers if provided.
See also
computeJacobianAndHessian computeJacobian computeHessian
Parameters
[in]inc_funFunction callback to the increment operator function
[in]eval_funFunction callback to the function evaluation
[out]jacobianThe resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix)
[out]hessianThe resulting Hessian matrix (warning: hessian must be preallocated as p x p matrix)
[in]multipliers(optional) Vector of multipliers for scaling individual Hessian terms [dim_f x 1].

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.

◆ getInstance()

virtual FiniteDifferencesInterface::Ptr corbo::FiniteDifferencesInterface::getInstance ( ) const
pure virtual

Return a newly allocated instances of the inherited class.

Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:02