25 #ifndef SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_COLLOCATION_H_ 26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_COLLOCATION_H_ 33 #ifdef MESSAGE_SUPPORT 34 #include <corbo-communication/messages/numerics/finite_differences_collocation.pb.h> 63 using Ptr = std::shared_ptr<FiniteDifferencesCollocationInterface>;
64 using UPtr = std::unique_ptr<FiniteDifferencesCollocationInterface>;
94 #ifdef MESSAGE_SUPPORT 95 virtual void toMessage(corbo::messages::FiniteDifferencesCollocation& message)
const {}
98 virtual void fromMessage(
const corbo::messages::FiniteDifferencesCollocation& message, std::stringstream* issues =
nullptr) {}
103 #define FACTORY_REGISTER_FD_COLLOCATION(type) FACTORY_REGISTER_OBJECT(type, FiniteDifferencesCollocationInterface) 129 assert(error.size() == x1.size());
133 error -= (x2 - x1) / dt;
163 assert(error.size() == x1.size());
164 assert(dt > 0 &&
"dt must be greater then zero!");
167 error -= (x2 - x1) / dt;
197 assert(error.size() == x1.size());
198 assert(dt > 0 &&
"dt must be greater then zero!");
200 system.
dynamics(0.5 * (x1 + x2), u1, error);
201 error -= (x2 - x1) / dt;
231 assert(error.size() == x1.size());
232 assert(dt > 0 &&
"dt must be greater then zero!");
234 Eigen::VectorXd f1(x1.size());
237 error = (x2 - x1) / dt - 0.5 * (f1 + error);
245 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_COLLOCATION_H_ void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
virtual void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error)=0
Compute differentiation error (system dynamics)
Collocation via forward differences.
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
std::unique_ptr< FiniteDifferencesCollocationInterface > UPtr
#define FACTORY_REGISTER_FD_COLLOCATION(type)
static Factory< FiniteDifferencesCollocationInterface > & getFactory()
Get access to the associated factory.
virtual void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const =0
Evaluate the system dynamics equation.
Collocation via backward differences.
virtual ~FiniteDifferencesCollocationInterface()=default
Virtual destructor.
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
static Factory & instance()
< Retrieve static instance of the factory
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
A matrix or vector expression mapping an existing expression.
Interface class for system dynamic equations.
Collocation via Crank-Nicolson differences.
Eigen::VectorXd StateVector
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
Collocation via midpoint differences.
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
Interface class for finite difference based collocation.
virtual FiniteDifferencesCollocationInterface::Ptr getInstance() const =0
Return a newly allocated instances of the inherited class.
Eigen::VectorXd InputVector
std::shared_ptr< FiniteDifferencesCollocationInterface > Ptr