Public Types | Public Member Functions | Private Attributes | List of all members
corbo::ClosedLoopControlTask Class Reference

Perform closed-loop control task. More...

#include <task_closed_loop_control.h>

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

Public Types

using Ptr = std::shared_ptr< ClosedLoopControlTask >
 
- Public Types inherited from corbo::TaskInterface
using Ptr = std::shared_ptr< TaskInterface >
 

Public Member Functions

 ClosedLoopControlTask ()
 Default constructor. More...
 
void getAvailableSignals (const Environment &environment, SignalTargetInterface &signal_target, const std::string &ns="") const override
 Retrieve available signals from the task. More...
 
TaskInterface::Ptr getInstance () const override
 Return a newly created shared instance of the implemented class. More...
 
void performTask (Environment &environment, SignalTargetInterface *signal_target=nullptr, std::string *msg=nullptr, const std::string &ns="") override
 Perform task. More...
 
void reset () override
 Reset task state. More...
 
void setControlReference (ReferenceTrajectoryInterface::Ptr ureference)
 Set control input reference trajectory. More...
 
void setStateReference (ReferenceTrajectoryInterface::Ptr xreference)
 Set state reference trajectory. More...
 
bool verify (const Environment &environment, std::string *msg=nullptr) const override
 Check if the environment and other settings satisfy all requirements for the given task. More...
 
- Public Member Functions inherited from corbo::TaskInterface
virtual ~TaskInterface ()
 Virtuel destructor. More...
 

Private Attributes

bool _compensate_cpu_time = false
 
bool _compensate_dead_time = false
 
OneStepPredictor _compensator
 
double _computation_delay = 0
 
FilterInterface::Ptr _computation_delay_filter
 
double _dt = 0.1
 
double _max_dt = CORBO_INF_DBL
 
double _min_dt = 0
 
bool _realtime_sync = false
 
double _sim_time = 10.0
 
TimeValueBuffer _time_value_buffer
 
ReferenceTrajectoryInterface::Ptr _ureference
 
bool _use_wall_time = false
 
ReferenceTrajectoryInterface::Ptr _xreference
 

Detailed Description

Perform closed-loop control task.

This class performs a closed-loop control task given a state and control input reference trajectory.

See also
TaskInterface Environment
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 task_closed_loop_control.h.

Member Typedef Documentation

◆ Ptr

Definition at line 53 of file task_closed_loop_control.h.

Constructor & Destructor Documentation

◆ ClosedLoopControlTask()

corbo::ClosedLoopControlTask::ClosedLoopControlTask ( )

Default constructor.

Definition at line 34 of file task_closed_loop_control.cpp.

Member Function Documentation

◆ getAvailableSignals()

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

Retrieve available signals from the task.

Register a-priori known signals at the signal target. Registration is optional. Note, during performTask() 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::TaskInterface.

Definition at line 41 of file task_closed_loop_control.cpp.

◆ getInstance()

TaskInterface::Ptr corbo::ClosedLoopControlTask::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Implements corbo::TaskInterface.

Definition at line 59 of file task_closed_loop_control.h.

◆ performTask()

void corbo::ClosedLoopControlTask::performTask ( Environment environment,
SignalTargetInterface signal_target = nullptr,
std::string *  msg = nullptr,
const std::string &  ns = "" 
)
overridevirtual

Perform task.

Parameters
[in]environmentStandard environment (plant, controller, observer)
[in,out]signal_targetTarget for occuring signals [optional]

Implements corbo::TaskInterface.

Definition at line 82 of file task_closed_loop_control.cpp.

◆ reset()

void corbo::ClosedLoopControlTask::reset ( )
overridevirtual

Reset task state.

Implements corbo::TaskInterface.

Definition at line 326 of file task_closed_loop_control.cpp.

◆ setControlReference()

void corbo::ClosedLoopControlTask::setControlReference ( ReferenceTrajectoryInterface::Ptr  ureference)
inline

Set control input reference trajectory.

Definition at line 68 of file task_closed_loop_control.h.

◆ setStateReference()

void corbo::ClosedLoopControlTask::setStateReference ( ReferenceTrajectoryInterface::Ptr  xreference)
inline

Set state reference trajectory.

Definition at line 66 of file task_closed_loop_control.h.

◆ verify()

bool corbo::ClosedLoopControlTask::verify ( const Environment environment,
std::string *  msg = nullptr 
) const
overridevirtual

Check if the environment and other settings satisfy all requirements for the given task.

This function can be called in order to check if all components and models are appropriate, e.g. if all input and output dimensions are chosen adequately.

Note, Environment::verify() might be invoked in order to check if controller, plant and observer are specified correctly and if they have matching dimensions.

Parameters
[in]environmentStandard environment (plant, controller, observer)
[out]msgThe string contains issue messages and hints if available [optional]
Returns
true if verification was successfull, false otherwise.

Implements corbo::TaskInterface.

Definition at line 268 of file task_closed_loop_control.cpp.

Member Data Documentation

◆ _compensate_cpu_time

bool corbo::ClosedLoopControlTask::_compensate_cpu_time = false
private

Definition at line 99 of file task_closed_loop_control.h.

◆ _compensate_dead_time

bool corbo::ClosedLoopControlTask::_compensate_dead_time = false
private

Definition at line 98 of file task_closed_loop_control.h.

◆ _compensator

OneStepPredictor corbo::ClosedLoopControlTask::_compensator
private

Definition at line 107 of file task_closed_loop_control.h.

◆ _computation_delay

double corbo::ClosedLoopControlTask::_computation_delay = 0
private

Definition at line 106 of file task_closed_loop_control.h.

◆ _computation_delay_filter

FilterInterface::Ptr corbo::ClosedLoopControlTask::_computation_delay_filter
private

Definition at line 109 of file task_closed_loop_control.h.

◆ _dt

double corbo::ClosedLoopControlTask::_dt = 0.1
private

Definition at line 95 of file task_closed_loop_control.h.

◆ _max_dt

double corbo::ClosedLoopControlTask::_max_dt = CORBO_INF_DBL
private

Definition at line 101 of file task_closed_loop_control.h.

◆ _min_dt

double corbo::ClosedLoopControlTask::_min_dt = 0
private

Definition at line 100 of file task_closed_loop_control.h.

◆ _realtime_sync

bool corbo::ClosedLoopControlTask::_realtime_sync = false
private

Definition at line 96 of file task_closed_loop_control.h.

◆ _sim_time

double corbo::ClosedLoopControlTask::_sim_time = 10.0
private

Definition at line 94 of file task_closed_loop_control.h.

◆ _time_value_buffer

TimeValueBuffer corbo::ClosedLoopControlTask::_time_value_buffer
private

Definition at line 108 of file task_closed_loop_control.h.

◆ _ureference

ReferenceTrajectoryInterface::Ptr corbo::ClosedLoopControlTask::_ureference
private

Definition at line 104 of file task_closed_loop_control.h.

◆ _use_wall_time

bool corbo::ClosedLoopControlTask::_use_wall_time = false
private

Definition at line 97 of file task_closed_loop_control.h.

◆ _xreference

ReferenceTrajectoryInterface::Ptr corbo::ClosedLoopControlTask::_xreference
private

Definition at line 103 of file task_closed_loop_control.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