Classes | Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
corbo::CommonSignalTarget Class Reference

General signal target to store incoming signals for post-processing. More...

#include <common_signal_target.h>

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

Classes

struct  SignalGroup
 Tree node containing a group of signals and a set of child tree nodes. More...
 

Public Types

using Ptr = std::shared_ptr< CommonSignalTarget >
 Virtual destructor. More...
 
- Public Types inherited from corbo::SignalTargetInterface
using Ptr = std::shared_ptr< SignalTargetInterface >
 

Public Member Functions

void clear ()
 Erase stored signals. More...
 
SignalGroupgetGroup (const std::string &full_group_name)
 
SignalInterface::Ptr getSignal (const std::string &full_signal_name)
 
const SignalGroupgetSignals () const
 Retrieve read-only-access to the underlying signal-tree. More...
 
SignalGroupgetSignalsRef ()
 
bool isEmpty ()
 
void registerMeasurement (const std::string &, int, const std::vector< std::string > &={}, bool zero_order_hold=false) override
 Register a measurement type at current target. More...
 
void registerTimeSeries (const std::string &, int, bool zero_order_hold=false) override
 Register a time series type at current target. More...
 
void removeSignal (const std::string &name)
 
void sendIndexedValues (IndexedValuesSignal::Ptr indexed_values) override
 Send signal containing values indexed by a single integer. More...
 
void sendIndexedValuesSet (IndexedValuesSetSignal::Ptr indexed_values_set) override
 Send signal containing a set of values indexed by integers (int to double[] map) More...
 
void sendMatrix (MatrixSignal::Ptr matrix) override
 Send a matrix to the target. More...
 
void sendMeasurement (Measurement::ConstPtr measurement) override
 Send a measurement to the target. More...
 
void sendTimeSeries (TimeSeriesSignal::Ptr time_series) override
 Send a time series to the target. More...
 
void setTopLevelGroupName (const std::string &name)
 
virtual ~CommonSignalTarget ()
 
- Public Member Functions inherited from corbo::SignalTargetInterface
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 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 (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 (const std::string &unique_name, TimeSeries::Ptr time_series)
 Send a time series to the target. More...
 
virtual ~SignalTargetInterface ()
 Virtual destructor. More...
 

Protected Member Functions

SignalGroupexpandGroups (const std::string full_signal_name, std::string *signal_name_out=nullptr, SignalInterface::Ptr *signal=nullptr)
 Parse full signal name, create tree-sub-groups if not found and return related signal group. More...
 

Private Attributes

SignalGroup _signals
 Root element of the signal tree. More...
 

Detailed Description

General signal target to store incoming signals for post-processing.

Signals are stored into an internal tree structure according to their namespaces/groups (refer to SignalInterface for a description of signal namespaces). These signals are then available for any post-processing purposes or file export.

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)
Todo:
Add possibility to reserve space for data (e.g. for TimeSeries object)

Definition at line 53 of file common_signal_target.h.

Member Typedef Documentation

◆ Ptr

Virtual destructor.

Definition at line 67 of file common_signal_target.h.

Constructor & Destructor Documentation

◆ ~CommonSignalTarget()

virtual corbo::CommonSignalTarget::~CommonSignalTarget ( )
inlinevirtual

Definition at line 68 of file common_signal_target.h.

Member Function Documentation

◆ clear()

void corbo::CommonSignalTarget::clear ( )

Erase stored signals.

Definition at line 320 of file common_signal_target.cpp.

◆ expandGroups()

CommonSignalTarget::SignalGroup * corbo::CommonSignalTarget::expandGroups ( const std::string  full_signal_name,
std::string *  signal_name_out = nullptr,
SignalInterface::Ptr signal = nullptr 
)
protected

Parse full signal name, create tree-sub-groups if not found and return related signal group.

This methods parses the provded signal name and expands the tree according to the signal namespaces/groups. The signal is not added to its corresponding group in the tree yet, but a pointer to its lowest containing group is returned.

Remarks
Make sure to check whether a signal with the same identifier is already present (refer to the third argument).
Parameters
[in]full_signal_nameSignal name containing all namespaces (separated by '/').
[out]signal_name_outSignal name without preceding namespaces/groups [optional]
[out]signalRetrieve a previous signal with the same identifier if any, otherwise return null [optional].
Returns
Pointer to the lowest containing group/namespace of the signal (which might be newly created during expansion).

Definition at line 265 of file common_signal_target.cpp.

◆ getGroup()

CommonSignalTarget::SignalGroup * corbo::CommonSignalTarget::getGroup ( const std::string &  full_group_name)

Definition at line 199 of file common_signal_target.cpp.

◆ getSignal()

SignalInterface::Ptr corbo::CommonSignalTarget::getSignal ( const std::string &  full_signal_name)

Definition at line 232 of file common_signal_target.cpp.

◆ getSignals()

const SignalGroup& corbo::CommonSignalTarget::getSignals ( ) const
inline

Retrieve read-only-access to the underlying signal-tree.

Returns
Signal tree structure starting with the root node of type CommonSignalTarget::SignalGroup

Definition at line 109 of file common_signal_target.h.

◆ getSignalsRef()

SignalGroup& corbo::CommonSignalTarget::getSignalsRef ( )
inline

Definition at line 111 of file common_signal_target.h.

◆ isEmpty()

bool corbo::CommonSignalTarget::isEmpty ( )
inline

Definition at line 103 of file common_signal_target.h.

◆ registerMeasurement()

void corbo::CommonSignalTarget::registerMeasurement ( const std::string &  unique_name,
int  value_dimension,
const std::vector< std::string > &  value_labels = {},
bool  zero_order_hold = false 
)
inlineoverridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 71 of file common_signal_target.h.

◆ registerTimeSeries()

void corbo::CommonSignalTarget::registerTimeSeries ( const std::string &  unique_name,
int  value_dimension,
bool  zero_order_hold = false 
)
inlineoverridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 77 of file common_signal_target.h.

◆ removeSignal()

void corbo::CommonSignalTarget::removeSignal ( const std::string &  name)

Definition at line 176 of file common_signal_target.cpp.

◆ sendIndexedValues()

void corbo::CommonSignalTarget::sendIndexedValues ( IndexedValuesSignal::Ptr  indexed_values)
overridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 92 of file common_signal_target.cpp.

◆ sendIndexedValuesSet()

void corbo::CommonSignalTarget::sendIndexedValuesSet ( IndexedValuesSetSignal::Ptr  indexed_values_set)
overridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 123 of file common_signal_target.cpp.

◆ sendMatrix()

void corbo::CommonSignalTarget::sendMatrix ( MatrixSignal::Ptr  matrix)
overridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 145 of file common_signal_target.cpp.

◆ sendMeasurement()

void corbo::CommonSignalTarget::sendMeasurement ( Measurement::ConstPtr  measurement)
overridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 34 of file common_signal_target.cpp.

◆ sendTimeSeries()

void corbo::CommonSignalTarget::sendTimeSeries ( TimeSeriesSignal::Ptr  time_series)
overridevirtual

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.

Implements corbo::SignalTargetInterface.

Definition at line 65 of file common_signal_target.cpp.

◆ setTopLevelGroupName()

void corbo::CommonSignalTarget::setTopLevelGroupName ( const std::string &  name)
inline

Definition at line 94 of file common_signal_target.h.

Member Data Documentation

◆ _signals

SignalGroup corbo::CommonSignalTarget::_signals
private

Root element of the signal tree.

Definition at line 135 of file common_signal_target.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