task_closed_loop_control.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_TASKS_INCLUDE_CORBO_TASKS_TASK_CLOSED_LOOP_CONTROL_H_
26 #define SRC_TASKS_INCLUDE_CORBO_TASKS_TASK_CLOSED_LOOP_CONTROL_H_
27 
29 
32 
33 #include <memory>
34 #include <string>
35 
36 namespace corbo {
37 
50 class ClosedLoopControlTask : public TaskInterface
51 {
52  public:
53  using Ptr = std::shared_ptr<ClosedLoopControlTask>;
54 
57 
58  // implements interface method
59  TaskInterface::Ptr getInstance() const override { return std::make_shared<ClosedLoopControlTask>(); }
60 
61  // implements interface method
62  void performTask(Environment& environment, SignalTargetInterface* signal_target = nullptr, std::string* msg = nullptr,
63  const std::string& ns = "") override;
64 
66  void setStateReference(ReferenceTrajectoryInterface::Ptr xreference) { _xreference = xreference; }
68  void setControlReference(ReferenceTrajectoryInterface::Ptr ureference) { _ureference = ureference; }
69 
70  // implements interface method
71  bool verify(const Environment& environment, std::string* msg = nullptr) const override;
72 
73  // implements interface method
74  void getAvailableSignals(const Environment& environment, SignalTargetInterface& signal_target, const std::string& ns = "") const override;
75 
76  // implements interface method
77  void reset() override;
78 
79 #ifdef MESSAGE_SUPPORT
80  void toMessage(messages::ClosedLoopControlTask& message) const;
81  void fromMessage(const messages::ClosedLoopControlTask& message, std::stringstream* issues = nullptr);
82 
83  // implements interface method
84  void toMessage(messages::Task& message) const override { toMessage(*message.mutable_closed_loop_control_task()); }
85  // implements interface method
86  void fromMessage(const messages::Task& message, std::stringstream* issues = nullptr) override
87  {
88  fromMessage(message.closed_loop_control_task(), issues);
89  }
90 
91 #endif
92 
93  private:
94  double _sim_time = 10.0;
95  double _dt = 0.1;
96  bool _realtime_sync = false;
97  bool _use_wall_time = false;
98  bool _compensate_dead_time = false;
99  bool _compensate_cpu_time = false;
100  double _min_dt = 0;
101  double _max_dt = CORBO_INF_DBL;
102 
105 
106  double _computation_delay = 0;
110 };
111 
113 
114 } // namespace corbo
115 
116 #endif // SRC_TASKS_INCLUDE_CORBO_TASKS_TASK_CLOSED_LOOP_CONTROL_H_
corbo::ClosedLoopControlTask::getAvailableSignals
void getAvailableSignals(const Environment &environment, SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the task.
Definition: task_closed_loop_control.cpp:63
corbo::ClosedLoopControlTask::_min_dt
double _min_dt
Definition: task_closed_loop_control.h:144
corbo::ClosedLoopControlTask::_max_dt
double _max_dt
Definition: task_closed_loop_control.h:145
corbo::SignalTargetInterface
Interface class for signal targets.
Definition: signal_target_interface.h:84
corbo::ClosedLoopControlTask::_computation_delay
double _computation_delay
Definition: task_closed_loop_control.h:150
corbo::TaskInterface::Ptr
std::shared_ptr< TaskInterface > Ptr
Definition: task_interface.h:107
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::Environment
Standard environment for control tasks.
Definition: environment.h:71
corbo::ClosedLoopControlTask::_ureference
ReferenceTrajectoryInterface::Ptr _ureference
Definition: task_closed_loop_control.h:148
corbo::ClosedLoopControlTask::Ptr
std::shared_ptr< ClosedLoopControlTask > Ptr
Definition: task_closed_loop_control.h:97
corbo::CORBO_INF_DBL
constexpr const double CORBO_INF_DBL
Representation for infinity (double version)
Definition: core/include/corbo-core/types.h:75
corbo::ClosedLoopControlTask::_use_wall_time
bool _use_wall_time
Definition: task_closed_loop_control.h:141
corbo::ClosedLoopControlTask::_compensate_cpu_time
bool _compensate_cpu_time
Definition: task_closed_loop_control.h:143
corbo::TimeValueBuffer
Time Delay Object for Piecewise-Constant Signals.
Definition: time_value_buffer.h:75
filter_interface.h
corbo::ClosedLoopControlTask::_xreference
ReferenceTrajectoryInterface::Ptr _xreference
Definition: task_closed_loop_control.h:147
corbo::OneStepPredictor
OneStepPredictor.
Definition: one_step_predictor.h:71
corbo::ClosedLoopControlTask::getInstance
TaskInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: task_closed_loop_control.h:103
corbo::ClosedLoopControlTask::ClosedLoopControlTask
ClosedLoopControlTask()
Default constructor.
Definition: task_closed_loop_control.cpp:56
corbo::ReferenceTrajectoryInterface::Ptr
std::shared_ptr< ReferenceTrajectoryInterface > Ptr
Definition: reference_trajectory.h:107
corbo::ClosedLoopControlTask
Perform closed-loop control task.
Definition: task_closed_loop_control.h:72
corbo::FilterInterface::Ptr
std::shared_ptr< FilterInterface > Ptr
Definition: filter_interface.h:97
task_interface.h
corbo::ClosedLoopControlTask::_realtime_sync
bool _realtime_sync
Definition: task_closed_loop_control.h:140
corbo::ClosedLoopControlTask::_time_value_buffer
TimeValueBuffer _time_value_buffer
Definition: task_closed_loop_control.h:152
corbo::ClosedLoopControlTask::setControlReference
void setControlReference(ReferenceTrajectoryInterface::Ptr ureference)
Set control input reference trajectory.
Definition: task_closed_loop_control.h:112
corbo::ClosedLoopControlTask::_dt
double _dt
Definition: task_closed_loop_control.h:139
corbo::ClosedLoopControlTask::setStateReference
void setStateReference(ReferenceTrajectoryInterface::Ptr xreference)
Set state reference trajectory.
Definition: task_closed_loop_control.h:110
corbo::ClosedLoopControlTask::_computation_delay_filter
FilterInterface::Ptr _computation_delay_filter
Definition: task_closed_loop_control.h:153
FACTORY_REGISTER_TASK
#define FACTORY_REGISTER_TASK(type)
Definition: task_interface.h:139
one_step_predictor.h
corbo::ClosedLoopControlTask::verify
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.
Definition: task_closed_loop_control.cpp:290
corbo::ClosedLoopControlTask::performTask
void performTask(Environment &environment, SignalTargetInterface *signal_target=nullptr, std::string *msg=nullptr, const std::string &ns="") override
Perform task.
Definition: task_closed_loop_control.cpp:104
corbo::ClosedLoopControlTask::_compensator
OneStepPredictor _compensator
Definition: task_closed_loop_control.h:151
corbo::ClosedLoopControlTask::_sim_time
double _sim_time
Definition: task_closed_loop_control.h:138
corbo::ClosedLoopControlTask::_compensate_dead_time
bool _compensate_dead_time
Definition: task_closed_loop_control.h:142
corbo::ClosedLoopControlTask::reset
void reset() override
Reset task state.
Definition: task_closed_loop_control.cpp:348


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:33