25 #ifndef SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_COLLOCATION_INTERFACE_H_ 26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_COLLOCATION_INTERFACE_H_ 33 #ifdef MESSAGE_SUPPORT 34 #include <corbo-communication/messages/numerics/collocation.pb.h> 66 using Ptr = std::shared_ptr<CollocationInterface>;
67 using UPtr = std::unique_ptr<CollocationInterface>;
97 std::vector<Eigen::VectorXd>& controls)
override 105 states.push_back(x1);
106 controls.push_back(u1);
108 if (dt < 1e-15)
return true;
112 for (
int i = 1; i <
n; ++i, t += range.
getStep())
114 double tau = (t - range.
getStart()) / dt;
115 states.push_back(x1 + tau * (x2 - x1));
116 controls.push_back(u1);
120 states.push_back(x2);
121 controls.push_back(u1);
126 #ifdef MESSAGE_SUPPORT 128 virtual void toMessage(corbo::messages::Collocation& message)
const {}
130 virtual void fromMessage(
const corbo::messages::Collocation& message, std::stringstream* issues =
nullptr) {}
133 void toMessage(corbo::messages::DynamicsEval& message)
const override { toMessage(*message.mutable_collocation()); }
135 void fromMessage(
const corbo::messages::DynamicsEval& message, std::stringstream* issues =
nullptr)
override 137 if (message.has_collocation()) fromMessage(message.collocation());
142 #define FACTORY_REGISTER_COLLOCATION(type) FACTORY_REGISTER_DYNAMICS_EVAL(type) 146 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_COLLOCATION_INTERFACE_H_ DynamicsEvalInterface::Ptr getInstance() const override=0
Return a newly allocated instances of the inherited class.
#define PRINT_ERROR_NAMED(msg)
int getNumInRange() const
Eigen::VectorXd StateVector
bool interpolate(const Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &u1, const Eigen::Ref< const Eigen::VectorXd > &x2, const Eigen::Ref< const Eigen::VectorXd > &u2, double dt, const SystemDynamicsInterface &system, const Range &range, std::vector< Eigen::VectorXd > &states, std::vector< Eigen::VectorXd > &controls) override
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override=0
Compute differentiation error (system dynamics)
std::shared_ptr< DynamicsEvalInterface > Ptr
std::shared_ptr< CollocationInterface > Ptr
virtual ~CollocationInterface()
Virtual destructor.
Interface class for solving and evaluating dynamics.
std::unique_ptr< CollocationInterface > UPtr
A matrix or vector expression mapping an existing expression.
Interface class for system dynamic equations.
Interface class for collocation based system dynamics evaluation.
Eigen::VectorXd InputVector