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

Dual mode controller. More...

#include <dual_mode_controller.h>

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

Public Types

using Ptr = std::shared_ptr< DualModeController >
 
- 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

 DualModeController ()=default
 
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...
 
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...
 
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 setLocalController (ControllerInterface::Ptr local_controller)
 
bool setWeightS (const Eigen::Ref< const Eigen::MatrixXd > &S)
 
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 Member Functions

bool isInsideInTerminalBall (const Eigen::Ref< const Eigen::VectorXd > &x0, const Eigen::Ref< const Eigen::VectorXd > &xf) const
 

Private Attributes

bool _first_run = true
 
double _gamma = 0.0
 
bool _initialized = false
 
ControllerInterface::Ptr _local_controller
 
bool _local_ctrl_active = false
 
double _min_dt = 0
 
PredictiveController _pred_controller
 
Eigen::MatrixXd _S
 
ControllerStatistics _statistics
 
bool _switch_dt = false
 
bool _switch_terminal_ball = false
 

Detailed Description

Dual mode controller.

Use predictive controller until some conditions are satisfied (terminal region, min dt) and then switch to an LQR.

See also
ControllerInterface LqrController PredictiveController
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 47 of file dual_mode_controller.h.

Member Typedef Documentation

◆ Ptr

Definition at line 50 of file dual_mode_controller.h.

Constructor & Destructor Documentation

◆ DualModeController()

corbo::DualModeController::DualModeController ( )
default

Member Function Documentation

◆ getAvailableSignals()

void corbo::DualModeController::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 107 of file dual_mode_controller.cpp.

◆ getControlDuration()

double corbo::DualModeController::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 89 of file dual_mode_controller.h.

◆ getControlInputDimension()

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

Return the control input dimension.

Implements corbo::ControllerInterface.

Definition at line 55 of file dual_mode_controller.h.

◆ getInstance()

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

Return a newly created shared instance of the implemented class.

Implements corbo::ControllerInterface.

Definition at line 75 of file dual_mode_controller.h.

◆ getInstanceStatic()

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

Definition at line 76 of file dual_mode_controller.h.

◆ getStateDimension()

int corbo::DualModeController::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 57 of file dual_mode_controller.h.

◆ getStatistics()

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

Reimplemented from corbo::ControllerInterface.

Definition at line 109 of file dual_mode_controller.h.

◆ hasPiecewiseConstantControls()

bool corbo::DualModeController::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 59 of file dual_mode_controller.h.

◆ initialize()

bool corbo::DualModeController::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 33 of file dual_mode_controller.cpp.

◆ isInsideInTerminalBall()

bool corbo::DualModeController::isInsideInTerminalBall ( const Eigen::Ref< const Eigen::VectorXd > &  x0,
const Eigen::Ref< const Eigen::VectorXd > &  xf 
) const
protected

Definition at line 101 of file dual_mode_controller.cpp.

◆ providesFutureControls()

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

Implements corbo::ControllerInterface.

Definition at line 64 of file dual_mode_controller.h.

◆ providesFutureStates()

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

Implements corbo::ControllerInterface.

Definition at line 69 of file dual_mode_controller.h.

◆ reset()

void corbo::DualModeController::reset ( )
overridevirtual

Reset internal controller state and caches.

Implements corbo::ControllerInterface.

Definition at line 115 of file dual_mode_controller.cpp.

◆ sendSignals()

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

Reimplemented from corbo::ControllerInterface.

Definition at line 123 of file dual_mode_controller.cpp.

◆ setLocalController()

void corbo::DualModeController::setLocalController ( ControllerInterface::Ptr  local_controller)
inline

Definition at line 96 of file dual_mode_controller.h.

◆ setWeightS()

bool corbo::DualModeController::setWeightS ( const Eigen::Ref< const Eigen::MatrixXd > &  S)

Definition at line 134 of file dual_mode_controller.cpp.

◆ step()

bool corbo::DualModeController::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 56 of file dual_mode_controller.cpp.

◆ supportsAsynchronousControl()

bool corbo::DualModeController::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 99 of file dual_mode_controller.h.

Member Data Documentation

◆ _first_run

bool corbo::DualModeController::_first_run = true
private

Definition at line 146 of file dual_mode_controller.h.

◆ _gamma

double corbo::DualModeController::_gamma = 0.0
private

Definition at line 142 of file dual_mode_controller.h.

◆ _initialized

bool corbo::DualModeController::_initialized = false
private

Definition at line 148 of file dual_mode_controller.h.

◆ _local_controller

ControllerInterface::Ptr corbo::DualModeController::_local_controller
private

Definition at line 134 of file dual_mode_controller.h.

◆ _local_ctrl_active

bool corbo::DualModeController::_local_ctrl_active = false
private

Definition at line 139 of file dual_mode_controller.h.

◆ _min_dt

double corbo::DualModeController::_min_dt = 0
private

Definition at line 144 of file dual_mode_controller.h.

◆ _pred_controller

PredictiveController corbo::DualModeController::_pred_controller
private

Definition at line 133 of file dual_mode_controller.h.

◆ _S

Eigen::MatrixXd corbo::DualModeController::_S
private

Definition at line 141 of file dual_mode_controller.h.

◆ _statistics

ControllerStatistics corbo::DualModeController::_statistics
private

Definition at line 131 of file dual_mode_controller.h.

◆ _switch_dt

bool corbo::DualModeController::_switch_dt = false
private

Definition at line 136 of file dual_mode_controller.h.

◆ _switch_terminal_ball

bool corbo::DualModeController::_switch_terminal_ball = false
private

Definition at line 137 of file dual_mode_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:02