Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
corbo::PredictiveController Class Reference

Predictive controller. More...

#include <predictive_controller.h>

Inheritance diagram for corbo::PredictiveController:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< PredictiveController >
 
- Public Types inherited from corbo::ControllerInterface
using ControlVector = Eigen::VectorXd
 
using Ptr = std::shared_ptr< ControllerInterface >
 
using StateVector = Eigen::VectorXd
 
using UPtr = std::unique_ptr< ControllerInterface >
 

Public Member Functions

bool getAutoUpdatePreviousControl () const
 
void getAvailableSignals (SignalTargetInterface &signal_target, const std::string &ns="") const override
 Retrieve available signals from the controller. More...
 
double getControlDuration () const override
 Return the duration for which the control u obtained from step() is valid (useful for asynchronous control) More...
 
int getControlInputDimension () const override
 Return the control input dimension. More...
 
ControllerInterface::Ptr getInstance () const override
 Return a newly created shared instance of the implemented class. More...
 
const intgetNumOcpIterations () const
 
OptimalControlProblemInterface::Ptr getOptimalControlProblem ()
 
int getStateDimension () const override
 Return the dimension of the required plant state/output. More...
 
ControllerStatistics::Ptr getStatistics () const override
 
bool hasPiecewiseConstantControls () const override
 Return true if the controller returns piecewise constant control pieces. More...
 
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. More...
 
const bool & isPublishPrediction () const
 
 PredictiveController ()
 
bool providesFutureControls () const override
 
bool providesFutureStates () const override
 
void reset () override
 Reset internal controller state and caches. More...
 
void sendSignals (double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
 
void setAutoUpdatePreviousControl (bool enable)
 
void setNumOcpIterations (int ocp_iter)
 
void setOptimalControlProblem (OptimalControlProblemInterface::Ptr ocp)
 
void setOutputControlSequenceLenght (bool activate)
 
void setOutputStateSequenceLenght (bool activate)
 
void setPublishPrediction (bool publish)
 
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
 
bool supportsAsynchronousControl () const override
 Specify whether the controllers step function is independent of dt and getControlDuration() returns a valid value. More...
 
- Public Member Functions inherited from corbo::ControllerInterface
virtual bool step (const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, ControlVector &u, SignalTargetInterface *signal_target=nullptr, const std::string &ns="")
 Perform actual controller step / control law computation. More...
 
virtual ~ControllerInterface ()
 Virtual destructor. More...
 

Static Public Member Functions

static Ptr getInstanceStatic ()
 
- Static Public Member Functions inherited from corbo::ControllerInterface
static Factory< ControllerInterface > & getFactory ()
 Get access to the associated factory. More...
 

Protected Attributes

bool _auto_update_prev_control = true
 
bool _initialized = false
 
int _num_ocp_iterations = 1
 
OptimalControlProblemInterface::Ptr _ocp
 
bool _output_control_sequence = false
 
bool _output_state_sequence = false
 
bool _publish_prediction = true
 
ControllerStatistics _statistics
 
TimeSeries::Ptr _u_ts
 
TimeSeries::Ptr _x_ts
 

Detailed Description

Predictive controller.

Implementation of a predictive controller that accepts a generic optimal control problem (OCP) that is solved within each step command.

The OCP is invoked repeatedly up to a user-specified number of iterations: refer to numOcpIterations().

See also
ControllerInterface LqrController PidController
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 50 of file predictive_controller.h.

Member Typedef Documentation

◆ Ptr

Definition at line 53 of file predictive_controller.h.

Constructor & Destructor Documentation

◆ PredictiveController()

corbo::PredictiveController::PredictiveController ( )

Definition at line 32 of file predictive_controller.cpp.

Member Function Documentation

◆ getAutoUpdatePreviousControl()

bool corbo::PredictiveController::getAutoUpdatePreviousControl ( ) const
inline

Definition at line 107 of file predictive_controller.h.

◆ getAvailableSignals()

void corbo::PredictiveController::getAvailableSignals ( SignalTargetInterface signal_target,
const std::string &  ns = "" 
) const
overridevirtual

Retrieve available signals from the controller.

Register a-priori known signals at the signal target. Registration is optional. Note, during step() execution further signals might occur without registration (in case the they are not known in advance or the implementation lacks a proper registration).

Parameters
[in,out]signal_targetTarget for occuring signals [optional]

Reimplemented from corbo::ControllerInterface.

Definition at line 81 of file predictive_controller.cpp.

◆ getControlDuration()

double corbo::PredictiveController::getControlDuration ( ) const
inlineoverridevirtual

Return the duration for which the control u obtained from step() is valid (useful for asynchronous control)

Reimplemented from corbo::ControllerInterface.

Definition at line 86 of file predictive_controller.h.

◆ getControlInputDimension()

int corbo::PredictiveController::getControlInputDimension ( ) const
inlineoverridevirtual

Return the control input dimension.

Implements corbo::ControllerInterface.

Definition at line 58 of file predictive_controller.h.

◆ getInstance()

ControllerInterface::Ptr corbo::PredictiveController::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Implements corbo::ControllerInterface.

Definition at line 69 of file predictive_controller.h.

◆ getInstanceStatic()

static Ptr corbo::PredictiveController::getInstanceStatic ( )
inlinestatic

Definition at line 70 of file predictive_controller.h.

◆ getNumOcpIterations()

const int& corbo::PredictiveController::getNumOcpIterations ( ) const
inline

Definition at line 97 of file predictive_controller.h.

◆ getOptimalControlProblem()

OptimalControlProblemInterface::Ptr corbo::PredictiveController::getOptimalControlProblem ( )
inline

Definition at line 73 of file predictive_controller.h.

◆ getStateDimension()

int corbo::PredictiveController::getStateDimension ( ) const
inlineoverridevirtual

Return the dimension of the required plant state/output.

Depending on the controller type, the state dimension can also be just the plant output or the complete measured or observed state vector.

Returns
the controllers state dimension

Implements corbo::ControllerInterface.

Definition at line 60 of file predictive_controller.h.

◆ getStatistics()

ControllerStatistics::Ptr corbo::PredictiveController::getStatistics ( ) const
inlineoverridevirtual

Reimplemented from corbo::ControllerInterface.

Definition at line 111 of file predictive_controller.h.

◆ hasPiecewiseConstantControls()

bool corbo::PredictiveController::hasPiecewiseConstantControls ( ) const
inlineoverridevirtual

Return true if the controller returns piecewise constant control pieces.

Returns
true if the controls are piecewise constant

Implements corbo::ControllerInterface.

Definition at line 62 of file predictive_controller.h.

◆ initialize()

bool corbo::PredictiveController::initialize ( const StateVector x,
ReferenceTrajectoryInterface expected_xref,
ReferenceTrajectoryInterface expected_uref,
const Duration expected_dt,
const Time t,
ReferenceTrajectoryInterface expected_sref = nullptr 
)
overridevirtual

Initialize the controller.

Initialization should be optional but it should facilitate memory allocation and trajectory initialization respectively warm starting.

Parameters
[in]xCurrent plant state [getStateDimension() x 1]
[in]expected_xrefState reference (writable in order to allow to the reference object to precompute caches)
[in]expected_urefControl reference (writable in order to allow to the reference object to precompute caches)
[in]expected_dtExpected sampling interval length (controller rate)
[in]tCurrent time stamp (can be sim-time or system-time, but compatible to state and control references)
Returns
true if initialization was successful, false otherwise.

Reimplemented from corbo::ControllerInterface.

Definition at line 34 of file predictive_controller.cpp.

◆ isPublishPrediction()

const bool& corbo::PredictiveController::isPublishPrediction ( ) const
inline

Definition at line 100 of file predictive_controller.h.

◆ providesFutureControls()

bool corbo::PredictiveController::providesFutureControls ( ) const
inlineoverridevirtual

Implements corbo::ControllerInterface.

Definition at line 64 of file predictive_controller.h.

◆ providesFutureStates()

bool corbo::PredictiveController::providesFutureStates ( ) const
inlineoverridevirtual

Implements corbo::ControllerInterface.

Definition at line 66 of file predictive_controller.h.

◆ reset()

void corbo::PredictiveController::reset ( )
overridevirtual

Reset internal controller state and caches.

Implements corbo::ControllerInterface.

Definition at line 94 of file predictive_controller.cpp.

◆ sendSignals()

void corbo::PredictiveController::sendSignals ( double  t,
SignalTargetInterface signal_target,
const std::string &  ns = "" 
) const
overridevirtual

Reimplemented from corbo::ControllerInterface.

Definition at line 99 of file predictive_controller.cpp.

◆ setAutoUpdatePreviousControl()

void corbo::PredictiveController::setAutoUpdatePreviousControl ( bool  enable)
inline

Definition at line 106 of file predictive_controller.h.

◆ setNumOcpIterations()

void corbo::PredictiveController::setNumOcpIterations ( int  ocp_iter)
inline

Definition at line 98 of file predictive_controller.h.

◆ setOptimalControlProblem()

void corbo::PredictiveController::setOptimalControlProblem ( OptimalControlProblemInterface::Ptr  ocp)
inline

Definition at line 72 of file predictive_controller.h.

◆ setOutputControlSequenceLenght()

void corbo::PredictiveController::setOutputControlSequenceLenght ( bool  activate)
inline

Definition at line 103 of file predictive_controller.h.

◆ setOutputStateSequenceLenght()

void corbo::PredictiveController::setOutputStateSequenceLenght ( bool  activate)
inline

Definition at line 104 of file predictive_controller.h.

◆ setPublishPrediction()

void corbo::PredictiveController::setPublishPrediction ( bool  publish)
inline

Definition at line 101 of file predictive_controller.h.

◆ step()

bool corbo::PredictiveController::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 = "" 
)
overridevirtual

Implements corbo::ControllerInterface.

Definition at line 46 of file predictive_controller.cpp.

◆ supportsAsynchronousControl()

bool corbo::PredictiveController::supportsAsynchronousControl ( ) const
inlineoverridevirtual

Specify whether the controllers step function is independent of dt and getControlDuration() returns a valid value.

Reimplemented from corbo::ControllerInterface.

Definition at line 89 of file predictive_controller.h.

Member Data Documentation

◆ _auto_update_prev_control

bool corbo::PredictiveController::_auto_update_prev_control = true
protected

Definition at line 136 of file predictive_controller.h.

◆ _initialized

bool corbo::PredictiveController::_initialized = false
protected

Definition at line 144 of file predictive_controller.h.

◆ _num_ocp_iterations

int corbo::PredictiveController::_num_ocp_iterations = 1
protected

Definition at line 138 of file predictive_controller.h.

◆ _ocp

OptimalControlProblemInterface::Ptr corbo::PredictiveController::_ocp
protected

Definition at line 130 of file predictive_controller.h.

◆ _output_control_sequence

bool corbo::PredictiveController::_output_control_sequence = false
protected

Definition at line 141 of file predictive_controller.h.

◆ _output_state_sequence

bool corbo::PredictiveController::_output_state_sequence = false
protected

Definition at line 142 of file predictive_controller.h.

◆ _publish_prediction

bool corbo::PredictiveController::_publish_prediction = true
protected

Definition at line 139 of file predictive_controller.h.

◆ _statistics

ControllerStatistics corbo::PredictiveController::_statistics
protected

Definition at line 134 of file predictive_controller.h.

◆ _u_ts

TimeSeries::Ptr corbo::PredictiveController::_u_ts
protected

Definition at line 132 of file predictive_controller.h.

◆ _x_ts

TimeSeries::Ptr corbo::PredictiveController::_x_ts
protected

Definition at line 131 of file predictive_controller.h.


The documentation for this class was generated from the following files:


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03