Interface class for finite difference approaches. More...
#include <finite_differences_interface.h>
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... | |
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. and/or
.
Definition at line 60 of file finite_differences_interface.h.
using corbo::FiniteDifferencesInterface::InputVector = Eigen::VectorXd |
Definition at line 67 of file finite_differences_interface.h.
using corbo::FiniteDifferencesInterface::Ptr = std::shared_ptr<FiniteDifferencesInterface> |
Definition at line 63 of file finite_differences_interface.h.
using corbo::FiniteDifferencesInterface::StateVector = Eigen::VectorXd |
Definition at line 66 of file finite_differences_interface.h.
using corbo::FiniteDifferencesInterface::UPtr = std::unique_ptr<FiniteDifferencesInterface> |
Definition at line 64 of file finite_differences_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 70 of file finite_differences_interface.h.
|
pure virtual |
Compute Hessian of a desired function.
Given a function with
. This method computes the
Hessian matrices of
(element-wise) and accumulates them (optionally with individual scale factors). In case
, the Hessian is as follows:
The Hessian is evaluated at .
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()
[in] | inc_fun | Function callback to the increment operator function |
[in] | eval_fun | Function callback to the function evaluation |
[in] | dim_f | Dimension of the function value vector (obtained from eval_fun) |
[out] | hessian | The 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.
|
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>
.
[in] | inc_fun | Function callback to the increment operator function |
[in] | eval_fun | Function callback to the function evaluation |
[in] | dim_f | Dimension of the function value vector (obtained from eval_fun) |
[out] | hessian | The 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.
|
pure virtual |
Compute Jacobian of a desired function.
Given a function with
. This method computes the Jacobian matrix
The Jacobian is evaluated at .
The function is defined by a function of the following prototype:
Hereby, fun
should return the function values via output argument values
as (n x 1) vector by implicitly taking the current working point 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:
Herebey, the first parameter determines which index (element in ) needs to be incremented, and the second contains the actual increment value.
Example implementation:
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()
[in] | inc_fun | Function callback to the increment operator function |
[in] | eval_fun | Function callback to the function evaluation |
[out] | jacobian | The resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix) |
Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.
|
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>
.
[in] | inc_fun | Function callback to the increment operator function |
[in] | eval_fun | Function callback to the function evaluation |
[out] | jacobian | The resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix) |
Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.
|
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()
[in] | inc_fun | Function callback to the increment operator function |
[in] | eval_fun | Function callback to the function evaluation |
[out] | jacobian | The resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix) |
[out] | hessian | The 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.
|
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>
.
[in] | inc_fun | Function callback to the increment operator function |
[in] | eval_fun | Function callback to the function evaluation |
[out] | jacobian | The resulting Jacobian matrix (warning: jacobian must be preallocated as n x p matrix) |
[out] | hessian | The 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.
|
pure virtual |
Return a newly allocated instances of the inherited class.
Implemented in corbo::CentralDifferences, and corbo::ForwardDifferences.