finite_differences.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_H_
26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_H_
27 
29 
30 #include <functional>
31 #include <memory>
32 
33 namespace corbo {
34 
50 {
51  public:
52  // Implements interface method
53  FiniteDifferencesInterface::Ptr getInstance() const override { return std::make_shared<ForwardDifferences>(); }
54 
67  template <typename IncFun, typename EvalFun>
68  static void jacobian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref<Eigen::MatrixXd> jacobian);
69 
88  template <typename IncFun, typename EvalFun>
89  static void hessian(IncFun inc_fun, EvalFun eval_fun, int dim_f, Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr);
90 
111  template <typename IncFun, typename EvalFun>
112  void jacobianHessian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref<Eigen::MatrixXd> jacobian, Eigen::Ref<Eigen::MatrixXd> hessian,
113  const double* multipliers = nullptr);
114 
115  // Implements interface method
116  void computeJacobian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun,
117  Eigen::Ref<Eigen::MatrixXd> jacobian) override;
118 
119  // Implements interface method
120  void computeJacobian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun,
121  Eigen::Ref<Eigen::MatrixXd> jacobian) override;
122 
123  // Implements interface method
124  void computeHessian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun, int dim_f,
125  Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr) override;
126 
127  // Implements interface method
128  void computeHessian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun, int dim_f,
129  Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr) override;
130 
131  // Implements interface method
132  void computeJacobianAndHessian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun,
134  const double* multipliers = nullptr) override;
135 
136  // Implements interface method
137  void computeJacobianAndHessian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun,
139  const double* multipliers = nullptr) override;
140 };
142 
143 
158 {
159  public:
160  // Implements interface method
161  FiniteDifferencesInterface::Ptr getInstance() const override { return std::make_shared<CentralDifferences>(); }
162 
175  template <typename IncFun, typename EvalFun>
176  static void jacobian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref<Eigen::MatrixXd> jacobian);
177 
178  template <typename IncFun, typename EvalFun>
179  static void hessian(IncFun inc_fun, EvalFun eval_fun, int dim_f, Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr);
180  // template <typename IncFun, typename EvalFun, typename WeightFun = double(int)>
181  // static void hessian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref<Eigen::MatrixXd> hessian, int dim_f = 1, WeightFun weight_fun = 0);
182 
183  template <typename IncFun, typename EvalFun>
184  void jacobianHessian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref<Eigen::MatrixXd> jacobian, Eigen::Ref<Eigen::MatrixXd> hessian,
185  const double* multipliers = nullptr);
186 
187  // Implements interface method
188  void computeJacobian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun,
189  Eigen::Ref<Eigen::MatrixXd> jacobian) override;
190 
191  // Implements interface method
192  void computeJacobian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun,
193  Eigen::Ref<Eigen::MatrixXd> jacobian) override;
194 
195  // Implements interface method
196  void computeHessian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun, int dim_f,
197  Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr) override;
198 
199  // Implements interface method
200  void computeHessian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun, int dim_f,
201  Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr) override;
202 
203  // Implements interface method
204  void computeJacobianAndHessian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun,
206  const double* multipliers = nullptr) override;
207 
208  // Implements interface method
209  void computeJacobianAndHessian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun,
211  const double* multipliers = nullptr) override;
212 };
214 
215 } // namespace corbo
216 
217 #include <corbo-numerics/finite_differences.hpp> // NOLINT(build/include_order)
218 
219 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_H_
static void jacobian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian)
Compute Jacobian of a desired function.
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) override
Compute Jacobian and Hessian of a desired function (overload which accepts a slightly different callb...
FiniteDifferencesInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
std::shared_ptr< FiniteDifferencesInterface > Ptr
Finite differences via central differences.
FiniteDifferencesInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
void computeJacobian(std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::Ref< Eigen::VectorXd >)> eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian) override
Compute Jacobian of a desired function.
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) override
Compute Hessian of a desired function (overload which accepts a slightly different callback function)...
void jacobianHessian(IncFun inc_fun, EvalFun eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian, Eigen::Ref< Eigen::MatrixXd > hessian, const double *multipliers=nullptr)
Compute Jacobian and Hessian of a desired function.
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
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) override
Compute Hessian of a desired function.
void computeJacobian2(std::function< void(int, const double &)> inc_fun, std::function< void(Eigen::VectorXd &)> eval_fun, Eigen::Ref< Eigen::MatrixXd > jacobian) override
Compute Jacobian of a desired function (overload which accepts a slightly different callback function...
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) override
Compute Jacobian and Hessian of a desired function.
#define FACTORY_REGISTER_FINITE_DIFFERENCES(type)
Finite differences via forward differences.
static void hessian(IncFun inc_fun, EvalFun eval_fun, int dim_f, Eigen::Ref< Eigen::MatrixXd > hessian, const double *multipliers=nullptr)
Compute Hessian of a desired function.
Interface class for finite difference approaches.


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