Go to the documentation of this file.
25 #ifndef SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_
50 class PredictiveController :
public ControllerInterface
53 using Ptr = std::shared_ptr<PredictiveController>;
76 bool initialize(
const StateVector&
x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
77 const Duration& expected_dt,
const Time& t, ReferenceTrajectoryInterface* sref =
nullptr)
override;
80 bool step(
const StateVector&
x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref,
const Duration& dt,
const Time& t,
82 ReferenceTrajectoryInterface* sref =
nullptr, ReferenceTrajectoryInterface* xinit =
nullptr,
83 ReferenceTrajectoryInterface* uinit =
nullptr,
const std::string& ns =
"")
override;
92 void getAvailableSignals(SignalTargetInterface& signal_target,
const std::string& ns =
"")
const override;
95 void reset()
override;
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_
void setPublishPrediction(bool publish)
Interface class for signal targets.
ControllerStatistics _statistics
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
const bool & isPublishPrediction() const
void setNumOcpIterations(int ocp_iter)
bool _output_control_sequence
bool providesFutureStates() const override
int getControlInputDimension() const override
Return the control input dimension.
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.
const int & getNumOcpIterations() const
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
ControllerStatistics::Ptr getStatistics() const override
std::shared_ptr< OptimalControlProblemInterface > Ptr
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
OptimalControlProblemInterface::Ptr getOptimalControlProblem()
bool getAutoUpdatePreviousControl() const
OptimalControlProblemInterface::Ptr _ocp
static Ptr getInstanceStatic()
void setOptimalControlProblem(OptimalControlProblemInterface::Ptr ocp)
std::shared_ptr< ControllerInterface > Ptr
int getStateDimension() const override
Return the dimension of the required plant state/output.
bool _output_state_sequence
void reset() override
Reset internal controller state and caches.
bool _auto_update_prev_control
std::shared_ptr< ControllerStatistics > Ptr
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
std::shared_ptr< PredictiveController > Ptr
Eigen::VectorXd StateVector
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
std::shared_ptr< TimeSeries > Ptr
void setAutoUpdatePreviousControl(bool enable)
void setOutputControlSequenceLenght(bool activate)
void setOutputStateSequenceLenght(bool activate)
bool providesFutureControls() const override
#define FACTORY_REGISTER_CONTROLLER(type)
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:03