25 #ifndef SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_DUAL_MODE_CONTROLLER_H_ 26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_DUAL_MODE_CONTROLLER_H_ 50 using Ptr = std::shared_ptr<DualModeController>;
105 void reset()
override;
111 return std::make_shared<ControllerStatistics>(
_statistics);
114 #ifdef MESSAGE_SUPPORT 115 void toMessage(corbo::messages::DualModeController& message)
const;
116 void fromMessage(
const corbo::messages::DualModeController& message, std::stringstream* issues =
nullptr);
119 void toMessage(corbo::messages::Controller& message)
const override { toMessage(*message.mutable_dual_mode_controller()); }
121 void fromMessage(
const corbo::messages::Controller& message, std::stringstream* issues =
nullptr)
override 123 fromMessage(message.dual_mode_controller(), issues);
155 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_DUAL_MODE_CONTROLLER_H_ int getControlInputDimension() const override
Return the control input dimension.
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
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.
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 sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
int getStateDimension() const override
Return the dimension of the required plant state/output.
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
std::shared_ptr< ControllerStatistics > Ptr
Interface class for signal targets.
Representation of time stamps.
bool providesFutureStates() const override
int getControlInputDimension() const override
Return the control input dimension.
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
bool providesFutureStates() const override
bool setWeightS(const Eigen::Ref< const Eigen::MatrixXd > &S)
void reset() override
Reset internal controller state and caches.
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
DualModeController()=default
int getStateDimension() const override
Return the dimension of the required plant state/output.
bool providesFutureControls() const override
ControllerStatistics::Ptr getStatistics() const override
#define FACTORY_REGISTER_CONTROLLER(type)
A matrix or vector expression mapping an existing expression.
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
static Ptr getInstanceStatic()
bool isInsideInTerminalBall(const Eigen::Ref< const Eigen::VectorXd > &x0, const Eigen::Ref< const Eigen::VectorXd > &xf) const
ControllerInterface::Ptr _local_controller
Interface class for reference trajectories.
Eigen::VectorXd StateVector
PredictiveController _pred_controller
bool providesFutureControls() const override
void setLocalController(ControllerInterface::Ptr local_controller)
ControllerStatistics _statistics
Interface class for controllers.
bool _switch_terminal_ball
std::shared_ptr< TimeSeries > 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
Representation of time durations.
std::shared_ptr< ControllerInterface > Ptr