finite_differences_interface.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_INTERFACE_H_
26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/time.h>
30 #include <corbo-core/types.h>
31 
32 #ifdef MESSAGE_SUPPORT
33 #include <corbo-communication/messages/numerics/finite_differences.pb.h>
34 #endif
35 
36 #include <functional>
37 #include <memory>
38 
39 namespace corbo {
40 
61 {
62  public:
63  using Ptr = std::shared_ptr<FiniteDifferencesInterface>;
64  using UPtr = std::unique_ptr<FiniteDifferencesInterface>;
65 
66  using StateVector = Eigen::VectorXd;
67  using InputVector = Eigen::VectorXd;
68 
72  virtual FiniteDifferencesInterface::Ptr getInstance() const = 0;
73 
129  virtual void computeJacobian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun,
130  Eigen::Ref<Eigen::MatrixXd> jacobian) = 0;
131 
145  virtual void computeJacobian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun,
146  Eigen::Ref<Eigen::MatrixXd> jacobian) = 0;
147 
178  virtual void computeHessian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun, int dim_f,
179  Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr) = 0;
180 
196  virtual void computeHessian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun, int dim_f,
197  Eigen::Ref<Eigen::MatrixXd> hessian, const double* multipliers = nullptr) = 0;
198 
228  virtual void computeJacobianAndHessian(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::Ref<Eigen::VectorXd>)> eval_fun,
230  const double* multipliers = nullptr) = 0;
231 
249  virtual void computeJacobianAndHessian2(std::function<void(int, const double&)> inc_fun, std::function<void(Eigen::VectorXd&)> eval_fun,
251  const double* multipliers = nullptr) = 0;
252 
253 #ifdef MESSAGE_SUPPORT
254  virtual void toMessage(messages::FiniteDifferences& message) const {}
257  virtual void fromMessage(const messages::FiniteDifferences& message, std::stringstream* issues = nullptr) {}
258 #endif
259 };
260 
262 #define FACTORY_REGISTER_FINITE_DIFFERENCES(type) FACTORY_REGISTER_OBJECT(type, FiniteDifferencesInterface)
263 
264 } // namespace corbo
265 
266 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_INTERFACE_H_
Generic factory object.
Definition: factory.h:68
virtual FiniteDifferencesInterface::Ptr getInstance() const =0
Return a newly allocated instances of the inherited class.
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 callb...
std::shared_ptr< FiniteDifferencesInterface > Ptr
virtual ~FiniteDifferencesInterface()
Virtual destructor.
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...
std::unique_ptr< FiniteDifferencesInterface > UPtr
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
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.
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)...
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.
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.
Interface class for finite difference approaches.


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