#include <one_step_predictor.h>
Public Types | |
using | ControlVector = Eigen::VectorXd |
using | StateVector = Eigen::VectorXd |
Public Member Functions | |
double | getDeadTime () |
bool | initialize () |
initialize the predictor More... | |
OneStepPredictor ()=default | |
Default constructor. More... | |
void | predict (const Eigen::Ref< const StateVector > &x0, std::vector< std::pair< double, ControlVector >> u_seq, double dt, Eigen::Ref< StateVector > x1) |
Predict x1 using t0, x0, u and dt (alias between x0 and x1 allowed) More... | |
void | setIntegrator (NumericalIntegratorExplicitInterface::Ptr integrator) |
Set a numerical integrator for continuous-time dynamics. More... | |
void | setSystemDynamics (SystemDynamicsInterface::Ptr dynamics) |
Set the system dynamics of the simulated plant. More... | |
Private Attributes | |
SystemDynamicsInterface::Ptr | _dynamics |
bool | _initialized = false |
NumericalIntegratorExplicitInterface::Ptr | _integrator |
Predict plant output for a single step, e.g. useful for CPU compenation in MPC control.
Definition at line 49 of file one_step_predictor.h.
using corbo::OneStepPredictor::ControlVector = Eigen::VectorXd |
Definition at line 53 of file one_step_predictor.h.
using corbo::OneStepPredictor::StateVector = Eigen::VectorXd |
Definition at line 52 of file one_step_predictor.h.
|
default |
Default constructor.
double corbo::OneStepPredictor::getDeadTime | ( | ) |
Definition at line 31 of file one_step_predictor.cpp.
bool corbo::OneStepPredictor::initialize | ( | ) |
initialize the predictor
Definition at line 33 of file one_step_predictor.cpp.
void corbo::OneStepPredictor::predict | ( | const Eigen::Ref< const StateVector > & | x0, |
std::vector< std::pair< double, ControlVector >> | u_seq, | ||
double | dt, | ||
Eigen::Ref< StateVector > | x1 | ||
) |
Predict x1 using t0, x0, u and dt (alias between x0 and x1 allowed)
Definition at line 42 of file one_step_predictor.cpp.
|
inline |
Set a numerical integrator for continuous-time dynamics.
Definition at line 69 of file one_step_predictor.h.
void corbo::OneStepPredictor::setSystemDynamics | ( | SystemDynamicsInterface::Ptr | dynamics | ) |
Set the system dynamics of the simulated plant.
Definition at line 80 of file one_step_predictor.cpp.
|
private |
Definition at line 79 of file one_step_predictor.h.
|
private |
Definition at line 82 of file one_step_predictor.h.
|
private |
Definition at line 80 of file one_step_predictor.h.