signal_target_interface.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_CORE_INCLUDE_CORBO_CORE_SIGNAL_TARGET_INTERFACE_H_
26 #define SRC_CORE_INCLUDE_CORBO_CORE_SIGNAL_TARGET_INTERFACE_H_
27 
28 #include <corbo-core/signals.h>
29 
30 #include <memory>
31 #include <string>
32 #include <vector>
33 
34 namespace corbo {
35 
62 class SignalTargetInterface
63 {
64  public:
65  using Ptr = std::shared_ptr<SignalTargetInterface>;
66 
68  virtual ~SignalTargetInterface() {}
69 
89  virtual void registerMeasurement(const std::string& unique_name, int value_dimension, const std::vector<std::string>& value_labels = {},
90  bool zero_order_hold = false) = 0;
91 
114  virtual void registerTimeSeries(const std::string& unique_name, int value_dimension, bool zero_order_hold = false) = 0;
115 
128  virtual void sendMeasurement(Measurement::ConstPtr measurement) = 0;
129 
147  virtual void sendMeasurement(const std::string& unique_name, double time, const std::vector<double>& values,
148  const std::vector<std::string>& value_labels = {})
149  {
150  Measurement::Ptr measurement = std::make_shared<Measurement>(time, values);
151  measurement->header.time = Time::now();
152  measurement->header.name = unique_name;
153  measurement->header.value_dimension = values.size();
154  measurement->getValueLabelsRef() = value_labels;
155  sendMeasurement(measurement);
156  }
157 
175  virtual void sendMeasurement(const std::string& unique_name, double time, const Eigen::Ref<const Eigen::VectorXd>& values,
176  const std::vector<std::string>& value_labels = {})
177  {
178  Measurement::Ptr measurement = std::make_shared<Measurement>(time, values);
179  measurement->header.time = Time::now();
180  measurement->header.name = unique_name;
181  measurement->header.value_dimension = values.rows();
182  measurement->getValueLabelsRef() = value_labels;
183  sendMeasurement(measurement);
184  }
185 
198  virtual void sendTimeSeries(TimeSeriesSignal::Ptr time_series) = 0;
199 
215  virtual void sendTimeSeries(const std::string& unique_name, TimeSeries::Ptr time_series)
216  {
217  TimeSeriesSignal::Ptr ts_signal = std::make_shared<TimeSeriesSignal>();
218  ts_signal->header.time = Time::now();
219  ts_signal->header.name = unique_name;
220  ts_signal->header.value_dimension = time_series->getValueDimension();
221  ts_signal->set(time_series);
222  sendTimeSeries(ts_signal);
223  }
224 
235  virtual void sendIndexedValues(IndexedValuesSignal::Ptr indexed_values) = 0;
236 
252  virtual void sendIndexedValues(const std::string& unique_name, int index, const std::vector<double>& values)
253  {
254  IndexedValuesSignal::Ptr indexed_values = std::make_shared<IndexedValuesSignal>(index, values);
255  indexed_values->header.time = Time::now();
256  indexed_values->header.name = unique_name;
257  indexed_values->header.value_dimension = 1; // for indexed values just one, since we won't have a fixed dimension, just statistical data
258  sendIndexedValues(indexed_values);
259  }
260 
276  virtual void sendIndexedValues(const std::string& unique_name, int index, const Eigen::Ref<const Eigen::VectorXd>& values)
277  {
278  IndexedValuesSignal::Ptr indexed_values = std::make_shared<IndexedValuesSignal>(index, values);
279  indexed_values->header.time = Time::now();
280  indexed_values->header.name = unique_name;
281  indexed_values->header.value_dimension = 1; // for indexed values just one, since we won't have a fixed dimension, just statistical data
282  sendIndexedValues(indexed_values);
283  }
284 
295  virtual void sendIndexedValuesSet(IndexedValuesSetSignal::Ptr indexed_values_set) = 0;
296 
307  virtual void sendMatrix(MatrixSignal::Ptr matrix) = 0;
308 
324  virtual void sendMatrix(const std::string& unique_name, const Eigen::Ref<const Eigen::MatrixXd>& matrix, const std::string& label = "")
325  {
326  MatrixSignal::Ptr matrix_sig = std::make_shared<MatrixSignal>(matrix, label);
327  matrix_sig->header.time = Time::now();
328  matrix_sig->header.name = unique_name;
329  matrix_sig->header.value_dimension = 1; // not relevant for this type yet (TODO(roesmann): unify)
330  sendMatrix(matrix_sig);
331  }
332 };
333 
334 } // namespace corbo
335 
336 #endif // SRC_CORE_INCLUDE_CORBO_CORE_SIGNAL_TARGET_INTERFACE_H_
corbo::MatrixSignal::Ptr
std::shared_ptr< MatrixSignal > Ptr
Definition: signals.h:564
corbo::Time::now
static Time now()
Retrieve current system time.
Definition: time.h:297
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::SignalTargetInterface::registerTimeSeries
virtual void registerTimeSeries(const std::string &unique_name, int value_dimension, bool zero_order_hold=false)=0
Register a time series type at current target.
corbo::SignalTargetInterface::Ptr
std::shared_ptr< SignalTargetInterface > Ptr
Definition: signal_target_interface.h:109
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: common.h:102
corbo::SignalTargetInterface::sendTimeSeries
virtual void sendTimeSeries(TimeSeriesSignal::Ptr time_series)=0
Send a time series to the target.
corbo::SignalTargetInterface::sendMeasurement
virtual void sendMeasurement(Measurement::ConstPtr measurement)=0
Send a measurement to the target.
corbo::Measurement::Ptr
std::shared_ptr< Measurement > Ptr
Definition: signals.h:196
corbo::SignalTargetInterface::sendIndexedValuesSet
virtual void sendIndexedValuesSet(IndexedValuesSetSignal::Ptr indexed_values_set)=0
Send signal containing a set of values indexed by integers (int to double[] map)
corbo::SignalTargetInterface::registerMeasurement
virtual void registerMeasurement(const std::string &unique_name, int value_dimension, const std::vector< std::string > &value_labels={}, bool zero_order_hold=false)=0
Register a measurement type at current target.
signals.h
corbo::SignalTargetInterface::sendMatrix
virtual void sendMatrix(MatrixSignal::Ptr matrix)=0
Send a matrix to the target.
corbo::IndexedValuesSignal::Ptr
std::shared_ptr< IndexedValuesSignal > Ptr
Definition: signals.h:415
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::SignalTargetInterface::sendIndexedValues
virtual void sendIndexedValues(IndexedValuesSignal::Ptr indexed_values)=0
Send signal containing values indexed by a single integer.
corbo::IndexedValuesSetSignal::Ptr
std::shared_ptr< IndexedValuesSetSignal > Ptr
Definition: signals.h:499
corbo::SignalTargetInterface::~SignalTargetInterface
virtual ~SignalTargetInterface()
Virtual destructor.
Definition: signal_target_interface.h:112
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::Measurement::ConstPtr
std::shared_ptr< const Measurement > ConstPtr
Definition: signals.h:197
corbo::TimeSeriesSignal::Ptr
std::shared_ptr< TimeSeriesSignal > Ptr
Definition: signals.h:269


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