Interface class for signal targets. More...
#include <signal_target_interface.h>
Public Types | |
using | Ptr = std::shared_ptr< SignalTargetInterface > |
Public Member Functions | |
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. More... | |
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. More... | |
virtual void | sendIndexedValues (IndexedValuesSignal::Ptr indexed_values)=0 |
Send signal containing values indexed by a single integer. More... | |
virtual void | sendIndexedValues (const std::string &unique_name, int index, const std::vector< double > &values) |
Send signal containing values indexed by a single integer. More... | |
virtual void | sendIndexedValues (const std::string &unique_name, int index, const Eigen::Ref< const Eigen::VectorXd > &values) |
Send signal containing values indexed by a single integer. More... | |
virtual void | sendIndexedValuesSet (IndexedValuesSetSignal::Ptr indexed_values_set)=0 |
Send signal containing a set of values indexed by integers (int to double[] map) More... | |
virtual void | sendMatrix (MatrixSignal::Ptr matrix)=0 |
Send a matrix to the target. More... | |
virtual void | sendMatrix (const std::string &unique_name, const Eigen::Ref< const Eigen::MatrixXd > &matrix, const std::string &label="") |
Send a matrix to the target. More... | |
virtual void | sendMeasurement (Measurement::ConstPtr measurement)=0 |
Send a measurement to the target. More... | |
virtual void | sendMeasurement (const std::string &unique_name, double time, const std::vector< double > &values, const std::vector< std::string > &value_labels={}) |
Send a measurement to the target. More... | |
virtual void | sendMeasurement (const std::string &unique_name, double time, const Eigen::Ref< const Eigen::VectorXd > &values, const std::vector< std::string > &value_labels={}) |
Send a measurement to the target. More... | |
virtual void | sendTimeSeries (TimeSeriesSignal::Ptr time_series)=0 |
Send a time series to the target. More... | |
virtual void | sendTimeSeries (const std::string &unique_name, TimeSeries::Ptr time_series) |
Send a time series to the target. More... | |
virtual | ~SignalTargetInterface () |
Virtual destructor. More... | |
Interface class for signal targets.
Signals are generated in certain modules like controllers, obervers or tasks in order to provide internal data (e.g. measurements, states, statistics, ...). Signals are usually derived from SignalInterface which implements an adapter to the actually data including general signal information (refer to SignalHeader).
Signals are identified using unique names. Signalnamespaces can be set using a "/" as delimiter, e.g.: /c this/is/a_signal/with/namespaces. Names can only be composed of alphanumeric characters and underscores (_).
In general signals are provided as data stream and hence multiple signals with different time stamps can share the same identifier (name). Targets need make sure to store or combine multiple signals of the same identifier appropriately.
Definition at line 62 of file signal_target_interface.h.
using corbo::SignalTargetInterface::Ptr = std::shared_ptr<SignalTargetInterface> |
Definition at line 65 of file signal_target_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 68 of file signal_target_interface.h.
|
pure virtual |
Register a measurement type at current target.
A measurement is meant to represent a vector of floating point numbers at a specified point in time. Hence, targets might store measurements of the same type (unique_name) into a TimeSeries object in order to record the whole sequence for batch-processing or visualization.
[in] | unique_name | Identifier for the current streams of measurements (same type, but different time-stamps allowed). |
[in] | value_dimension | Dimension of the measurement vector (number of floating point values). |
[in] | value_labels | Labels for individual components of the measurement vector, e.g. for data export or plotting (axes labels). |
[in] | zero_order_hold | Specify whether the signal is intended to be holded (zero order hold) between two consecutive values. |
Implemented in corbo::CommonSignalTarget.
|
pure virtual |
Register a time series type at current target.
A TimeSeries is meant to represent a sequence of value vectors or measurements.
The channel associated with unique_name
might be used to send a single TimeSeriesSignal or a stream of TimeSeriesSignal objects. Hence, targets might store signals of the same type (unique_name) into a collection of TimeSeries objects in order to record the whole sequence for batch-processing or visualization.
[in] | unique_name | Identifier for the current streams of measurements (same type, but different time-stamps allowed). |
[in] | value_dimension | Dimension of the measurement vector (number of floating point values). |
[in] | zero_order_hold | Specify whether the signal is intended to be holded (zero order hold) between two consecutive values. |
Implemented in corbo::CommonSignalTarget.
|
pure virtual |
Send signal containing values indexed by a single integer.
[in] | indexed_values | IndexedValuesSignal object with valid header to be sent. |
Implemented in corbo::CommonSignalTarget.
|
inlinevirtual |
Send signal containing values indexed by a single integer.
This method overloads sendIndexedValues(IndexedValuesSignal::Ptr indexed_values) and constructs a IndexedValuesSignal object from a given unique_name, index and value vector (provided as std::vector<double> type).
The SignalHeader time-stamp is set to the current time.
[in] | unique_name | Identifier for the current streams of values (same type, but different time-stamps allowed). |
[in] | index | Index as (non-unique) identifier for the current value vector (values with same identifier will be stacked) |
[in] | values | Value vector (STL version) |
Definition at line 252 of file signal_target_interface.h.
|
inlinevirtual |
Send signal containing values indexed by a single integer.
This method overloads sendIndexedValues(IndexedValuesSignal::Ptr indexed_values) and constructs a IndexedValuesSignal object from a given unique_name, index and value vector (provided as Eigen::VectorXd type).
The SignalHeader time-stamp is set to the current time.
[in] | unique_name | Identifier for the current streams of values (same type, but different time-stamps allowed). |
[in] | index | Index as (non-unique) identifier for the current value vector (values with same identifier will be stacked) |
[in] | values | Value vector (Eigen::VectorXd version) |
Definition at line 276 of file signal_target_interface.h.
|
pure virtual |
Send signal containing a set of values indexed by integers (int to double[] map)
[in] | indexed_values_set | IndexedValuesSetSignal object with valid header to be sent. |
Implemented in corbo::CommonSignalTarget.
|
pure virtual |
Send a matrix to the target.
[in] | time_series | TimeSeriesSignal object with valid header to be sent. |
Implemented in corbo::CommonSignalTarget.
|
inlinevirtual |
Send a matrix to the target.
This method overloads sendMatrix(MatrixSignal::Ptr matrix) and constructs a MatrixSignal object from a given unique_name and matrix (provided as Eigen::MatrixXd type). Each matrix can be associated with an additional label.
The SignalHeader time-stamp is set to the current time.
[in] | unique_name | Identifier for the current streams of matrices (same type, but different time-stamps allowed). |
[in] | matrix | Matrix with actual values (Eigen::MatrixXd version) |
[in] | label | Optional label which describes the content of the matrix [optional] |
Definition at line 324 of file signal_target_interface.h.
|
pure virtual |
Send a measurement to the target.
Refer to registerMeasurement() for a detailed description.
[in] | measurement | Measurement object with valid header to be sent. |
Implemented in corbo::CommonSignalTarget.
|
inlinevirtual |
Send a measurement to the target.
Refer to registerMeasurement() for a detailed description. This method overloads sendMeasurement(Measurement::Ptr measurement) and constructs a Measurement object from a given unique_name, time and value vector (provided as std::vector<double> type).
Note, the time corresponds to the value vector and not to the SignalHeader time-stamp. The SignalHeader time-stamp is set to the current time.
[in] | unique_name | Identifier for the current streams of measurements (same type, but different time-stamps allowed). |
[in] | time | Time at which the values are recorded (usually in seconds). |
[in] | values | Value vector containing the actual recorded data. |
Definition at line 147 of file signal_target_interface.h.
|
inlinevirtual |
Send a measurement to the target.
Refer to registerMeasurement() for a detailed description. This method overloads sendMeasurement(Measurement::Ptr measurement) and constructs a Measurement object from a given unique_name, time and value vector (provided as Eigen::VectorXd type).
Note, the time corresponds to the value vector and not to the SignalHeader time-stamp. The SignalHeader time-stamp is set to the current time.
[in] | unique_name | Identifier for the current streams of measurements (same type, but different time-stamps allowed). |
[in] | time | Time at which the values are recorded (usually in seconds). |
[in] | values | Value vector containing the actual recorded data. |
Definition at line 175 of file signal_target_interface.h.
|
pure virtual |
Send a time series to the target.
Refer to registerTimeSeries() for a detailed description.
[in] | time_series | TimeSeriesSignal object with valid header to be sent. |
Implemented in corbo::CommonSignalTarget.
|
inlinevirtual |
Send a time series to the target.
Refer to registerTimeSeries() for a detailed description. This method overloads sendTimeSeries(TimeSeriesSignal::Ptr time_series) and constructs a TimeSeriesSignal object from a given unique_name, and TimeSeries object.
[in] | unique_name | Identifier for the current stream of TimeSeriesSignal objects |
[in] | time_series | Shared TimeSeries object |
Definition at line 215 of file signal_target_interface.h.