Public Types | Public Member Functions | List of all members
corbo::SignalTargetInterface Class Referenceabstract

Interface class for signal targets. More...

#include <signal_target_interface.h>

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

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...
 

Detailed Description

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.

See also
SignalTargetInterface SignalTargetRPC YamlExporter
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 62 of file signal_target_interface.h.

Member Typedef Documentation

◆ Ptr

Definition at line 65 of file signal_target_interface.h.

Constructor & Destructor Documentation

◆ ~SignalTargetInterface()

virtual corbo::SignalTargetInterface::~SignalTargetInterface ( )
inlinevirtual

Virtual destructor.

Definition at line 68 of file signal_target_interface.h.

Member Function Documentation

◆ registerMeasurement()

virtual void corbo::SignalTargetInterface::registerMeasurement ( const std::string &  unique_name,
int  value_dimension,
const std::vector< std::string > &  value_labels = {},
bool  zero_order_hold = false 
)
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.

Remarks
Signal registration is optional (at least for the current set of targets), but it is recommended for pre-memory-allocation purposes and e.g. for online plotting support in the GUI.
See also
Measurement sendMeasurement
Parameters
[in]unique_nameIdentifier for the current streams of measurements (same type, but different time-stamps allowed).
[in]value_dimensionDimension of the measurement vector (number of floating point values).
[in]value_labelsLabels for individual components of the measurement vector, e.g. for data export or plotting (axes labels).
[in]zero_order_holdSpecify whether the signal is intended to be holded (zero order hold) between two consecutive values.

Implemented in corbo::CommonSignalTarget.

◆ registerTimeSeries()

virtual void corbo::SignalTargetInterface::registerTimeSeries ( const std::string &  unique_name,
int  value_dimension,
bool  zero_order_hold = false 
)
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.

Remarks
Make sure to set TimeSeries::setTimeFromStart() in order to specify a valid sequence of TimeSeries objects w.r.t. time. The SignalHeader time stamp is currently not in use for this purpose.
Signal registration is optional (at least for the current set of targets), but it is recommended for pre-memory-allocation purposes and e.g. for online plotting support in the GUI.
See also
TimeSeriesSignal TimeSeries sendTimeSeries
Parameters
[in]unique_nameIdentifier for the current streams of measurements (same type, but different time-stamps allowed).
[in]value_dimensionDimension of the measurement vector (number of floating point values).
[in]zero_order_holdSpecify whether the signal is intended to be holded (zero order hold) between two consecutive values.

Implemented in corbo::CommonSignalTarget.

◆ sendIndexedValues() [1/3]

virtual void corbo::SignalTargetInterface::sendIndexedValues ( IndexedValuesSignal::Ptr  indexed_values)
pure virtual

Send signal containing values indexed by a single integer.

Warning
Make sure to provide a valid SignalHeader including a unique name or use on of the method overloads for a more convenient usage.
See also
IndexedValuesSignal IndexedValuesSetSignal
Parameters
[in]indexed_valuesIndexedValuesSignal object with valid header to be sent.

Implemented in corbo::CommonSignalTarget.

◆ sendIndexedValues() [2/3]

virtual void corbo::SignalTargetInterface::sendIndexedValues ( const std::string &  unique_name,
int  index,
const std::vector< double > &  values 
)
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.

See also
IndexedValuesSignal IndexedValuesSetSignal
Parameters
[in]unique_nameIdentifier for the current streams of values (same type, but different time-stamps allowed).
[in]indexIndex as (non-unique) identifier for the current value vector (values with same identifier will be stacked)
[in]valuesValue vector (STL version)

Definition at line 252 of file signal_target_interface.h.

◆ sendIndexedValues() [3/3]

virtual void corbo::SignalTargetInterface::sendIndexedValues ( const std::string &  unique_name,
int  index,
const Eigen::Ref< const Eigen::VectorXd > &  values 
)
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.

See also
IndexedValuesSignal IndexedValuesSetSignal
Parameters
[in]unique_nameIdentifier for the current streams of values (same type, but different time-stamps allowed).
[in]indexIndex as (non-unique) identifier for the current value vector (values with same identifier will be stacked)
[in]valuesValue vector (Eigen::VectorXd version)

Definition at line 276 of file signal_target_interface.h.

◆ sendIndexedValuesSet()

virtual void corbo::SignalTargetInterface::sendIndexedValuesSet ( IndexedValuesSetSignal::Ptr  indexed_values_set)
pure virtual

Send signal containing a set of values indexed by integers (int to double[] map)

Warning
Make sure to provide a valid SignalHeader including a unique name or use on of the method overloads for a more convenient usage.
See also
IndexedValuesSetSignal IndexedValuesSignal
Parameters
[in]indexed_values_setIndexedValuesSetSignal object with valid header to be sent.

Implemented in corbo::CommonSignalTarget.

◆ sendMatrix() [1/2]

virtual void corbo::SignalTargetInterface::sendMatrix ( MatrixSignal::Ptr  matrix)
pure virtual

Send a matrix to the target.

Warning
Make sure to provide a valid SignalHeader including a unique name or use on of the method overloads for a more convenient usage.
See also
TimeSeriesSignal TimeSeries registerTimeSeries
Parameters
[in]time_seriesTimeSeriesSignal object with valid header to be sent.

Implemented in corbo::CommonSignalTarget.

◆ sendMatrix() [2/2]

virtual void corbo::SignalTargetInterface::sendMatrix ( const std::string &  unique_name,
const Eigen::Ref< const Eigen::MatrixXd > &  matrix,
const std::string &  label = "" 
)
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.

See also
MatrixSignal MatrixSetSignal
Parameters
[in]unique_nameIdentifier for the current streams of matrices (same type, but different time-stamps allowed).
[in]matrixMatrix with actual values (Eigen::MatrixXd version)
[in]labelOptional label which describes the content of the matrix [optional]

Definition at line 324 of file signal_target_interface.h.

◆ sendMeasurement() [1/3]

virtual void corbo::SignalTargetInterface::sendMeasurement ( Measurement::ConstPtr  measurement)
pure virtual

Send a measurement to the target.

Refer to registerMeasurement() for a detailed description.

Warning
Make sure to provide a valid SignalHeader including a unique name or use on of the method overloads for a more convenient usage.
See also
Measurement registerMeasurement
Parameters
[in]measurementMeasurement object with valid header to be sent.

Implemented in corbo::CommonSignalTarget.

◆ sendMeasurement() [2/3]

virtual void corbo::SignalTargetInterface::sendMeasurement ( const std::string &  unique_name,
double  time,
const std::vector< double > &  values,
const std::vector< std::string > &  value_labels = {} 
)
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.

See also
Measurement registerMeasurement
Parameters
[in]unique_nameIdentifier for the current streams of measurements (same type, but different time-stamps allowed).
[in]timeTime at which the values are recorded (usually in seconds).
[in]valuesValue vector containing the actual recorded data.

Definition at line 147 of file signal_target_interface.h.

◆ sendMeasurement() [3/3]

virtual void corbo::SignalTargetInterface::sendMeasurement ( const std::string &  unique_name,
double  time,
const Eigen::Ref< const Eigen::VectorXd > &  values,
const std::vector< std::string > &  value_labels = {} 
)
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.

See also
Measurement registerMeasurement
Parameters
[in]unique_nameIdentifier for the current streams of measurements (same type, but different time-stamps allowed).
[in]timeTime at which the values are recorded (usually in seconds).
[in]valuesValue vector containing the actual recorded data.

Definition at line 175 of file signal_target_interface.h.

◆ sendTimeSeries() [1/2]

virtual void corbo::SignalTargetInterface::sendTimeSeries ( TimeSeriesSignal::Ptr  time_series)
pure virtual

Send a time series to the target.

Refer to registerTimeSeries() for a detailed description.

Warning
Make sure to provide a valid SignalHeader including a unique name or use on of the method overloads for a more convenient usage.
See also
TimeSeriesSignal TimeSeries registerTimeSeries
Parameters
[in]time_seriesTimeSeriesSignal object with valid header to be sent.

Implemented in corbo::CommonSignalTarget.

◆ sendTimeSeries() [2/2]

virtual void corbo::SignalTargetInterface::sendTimeSeries ( const std::string &  unique_name,
TimeSeries::Ptr  time_series 
)
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.

See also
TimeSeriesSignal TimeSeries registerTimeSeries
Todo:
Make sure that everything is thread-safe if we forward a shared_ptr
Parameters
[in]unique_nameIdentifier for the current stream of TimeSeriesSignal objects
[in]time_seriesShared TimeSeries object

Definition at line 215 of file signal_target_interface.h.


The documentation for this class was generated from the following file:


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03