25 #ifndef SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_ 26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_ 53 using Ptr = std::shared_ptr<PredictiveController>;
95 void reset()
override;
113 return std::make_shared<ControllerStatistics>(
_statistics);
116 #ifdef MESSAGE_SUPPORT 117 void toMessage(corbo::messages::PredictiveController& message)
const;
118 void fromMessage(
const corbo::messages::PredictiveController& message, std::stringstream* issues =
nullptr);
121 void toMessage(corbo::messages::Controller& message)
const override { toMessage(*message.mutable_predictive_controller()); }
123 void fromMessage(
const corbo::messages::Controller& message, std::stringstream* issues =
nullptr)
override 125 fromMessage(message.predictive_controller(), issues);
151 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_ const int & getNumOcpIterations() const
bool _output_control_sequence
int getControlInputDimension() const override
Return the control input dimension.
ControllerStatistics::Ptr getStatistics() const override
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
void setOutputStateSequenceLenght(bool activate)
void setPublishPrediction(bool publish)
ControllerStatistics _statistics
const bool & isPublishPrediction() const
std::shared_ptr< ControllerStatistics > Ptr
std::shared_ptr< OptimalControlProblemInterface > Ptr
Interface class for signal targets.
Representation of time stamps.
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
OptimalControlProblemInterface::Ptr _ocp
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
bool providesFutureStates() const override
bool _output_state_sequence
int getStateDimension() const override
Return the dimension of the required plant state/output.
void reset() override
Reset internal controller state and caches.
OptimalControlProblemInterface::Ptr getOptimalControlProblem()
#define FACTORY_REGISTER_CONTROLLER(type)
bool step(const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface *signal_target=nullptr, ReferenceTrajectoryInterface *sref=nullptr, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr, const std::string &ns="") override
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
void setAutoUpdatePreviousControl(bool enable)
void setOptimalControlProblem(OptimalControlProblemInterface::Ptr ocp)
void setOutputControlSequenceLenght(bool activate)
static Ptr getInstanceStatic()
Interface class for reference trajectories.
Eigen::VectorXd StateVector
bool getAutoUpdatePreviousControl() const
bool providesFutureControls() const override
Interface class for controllers.
void setNumOcpIterations(int ocp_iter)
std::shared_ptr< TimeSeries > Ptr
bool _auto_update_prev_control
Representation of time durations.
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
std::shared_ptr< ControllerInterface > Ptr
bool initialize(const StateVector &x, ReferenceTrajectoryInterface &expected_xref, ReferenceTrajectoryInterface &expected_uref, const Duration &expected_dt, const Time &t, ReferenceTrajectoryInterface *sref=nullptr) override
Initialize the controller.