Public Types | Public Member Functions | Private Attributes | List of all members
corbo::TimeSeriesSignal Class Reference

Time Series signal (trajectory resp. sequence of values w.r.t. time) More...

#include <signals.h>

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

Public Types

using ConstPtr = std::shared_ptr< const TimeSeriesSignal >
 
using Ptr = std::shared_ptr< TimeSeriesSignal >
 
- Public Types inherited from corbo::SignalInterface
using ConstPtr = std::shared_ptr< const SignalInterface >
 
using Ptr = std::shared_ptr< SignalInterface >
 

Public Member Functions

void add (const Measurement &measurement)
 Add measurement (time and value pair) More...
 
void add (double time, const Eigen::Ref< const Eigen::VectorXd > &values)
 Add time and value vector pair (Eigen version) More...
 
void add (double time, const std::vector< double > &values)
 Add time and value vector pair (STL version) More...
 
const TimeSeriesgetTimeSeries () const
 Read access to the underlying time series object (returns null if not initialized) More...
 
TimeSeries::Ptr getTimeSeriesPtr () const
 Return shared pointer of the underlying time series (can be empty if not initialized) More...
 
TimeSeriesgetTimeSeriesRaw ()
 Raw access to the underlying time series object (returns null if not initialized) More...
 
SignalType getType () const override
 Get the signal type according to enumeration SignalType. More...
 
void getValueLabels (std::vector< std::string > &sublabels) const override
 Return labels for the underlying components of the signal (e.g. axes labels) More...
 
bool isEmpty () const
 Check if the time series is empty. More...
 
void set (TimeSeries::Ptr time_series)
 Set time series (and override any existing) More...
 
void set (const Eigen::Ref< const Eigen::VectorXd > &time, const Eigen::Ref< const Eigen::MatrixXd > &values_matrix, double time_from_start=0.0)
 Set time vector and values matrix. More...
 
void setTimeFromStart (double time_from_start)
 Set time from start (offset to all time stamps in time()) More...
 
 TimeSeriesSignal ()
 Default constructor. More...
 
 TimeSeriesSignal (int value_dim)
 Construct empty time series signal with a dresired value vector dimension. More...
 
 TimeSeriesSignal (TimeSeries::Ptr time_series)
 Construct time series signal from a time_series object (avoids copying) More...
 
 TimeSeriesSignal (const Measurement &measurment)
 Constructs and initializes time series signal and adds a single measurement. More...
 
- Public Member Functions inherited from corbo::SignalInterface
virtual ~SignalInterface ()
 Virtual destructor. More...
 

Private Attributes

TimeSeries::Ptr _time_series
 

Additional Inherited Members

- Public Attributes inherited from corbo::SignalInterface
SignalHeader header
 The header of the signal. More...
 

Detailed Description

Time Series signal (trajectory resp. sequence of values w.r.t. time)

A time series is meant to represent a sequence of vectors of floating point numbers with individual time stamps. A time series might also be interpreted as a discrete-time trajectory. This class wraps a TimeSeries object into a signal along with a SignalHeader.

See also
TimeSeries SignalInterface Measurement
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 244 of file signals.h.

Member Typedef Documentation

◆ ConstPtr

using corbo::TimeSeriesSignal::ConstPtr = std::shared_ptr<const TimeSeriesSignal>

Definition at line 248 of file signals.h.

◆ Ptr

Definition at line 247 of file signals.h.

Constructor & Destructor Documentation

◆ TimeSeriesSignal() [1/4]

corbo::TimeSeriesSignal::TimeSeriesSignal ( )
inline

Default constructor.

Definition at line 251 of file signals.h.

◆ TimeSeriesSignal() [2/4]

corbo::TimeSeriesSignal::TimeSeriesSignal ( int  value_dim)
inlineexplicit

Construct empty time series signal with a dresired value vector dimension.

Definition at line 253 of file signals.h.

◆ TimeSeriesSignal() [3/4]

corbo::TimeSeriesSignal::TimeSeriesSignal ( TimeSeries::Ptr  time_series)
inlineexplicit

Construct time series signal from a time_series object (avoids copying)

Definition at line 255 of file signals.h.

◆ TimeSeriesSignal() [4/4]

corbo::TimeSeriesSignal::TimeSeriesSignal ( const Measurement measurment)
inlineexplicit

Constructs and initializes time series signal and adds a single measurement.

Definition at line 257 of file signals.h.

Member Function Documentation

◆ add() [1/3]

void corbo::TimeSeriesSignal::add ( const Measurement measurement)

Add measurement (time and value pair)

Definition at line 63 of file signals.cpp.

◆ add() [2/3]

void corbo::TimeSeriesSignal::add ( double  time,
const Eigen::Ref< const Eigen::VectorXd > &  values 
)

Add time and value vector pair (Eigen version)

Definition at line 74 of file signals.cpp.

◆ add() [3/3]

void corbo::TimeSeriesSignal::add ( double  time,
const std::vector< double > &  values 
)

Add time and value vector pair (STL version)

Definition at line 80 of file signals.cpp.

◆ getTimeSeries()

const TimeSeries* corbo::TimeSeriesSignal::getTimeSeries ( ) const
inline

Read access to the underlying time series object (returns null if not initialized)

Definition at line 298 of file signals.h.

◆ getTimeSeriesPtr()

TimeSeries::Ptr corbo::TimeSeriesSignal::getTimeSeriesPtr ( ) const
inline

Return shared pointer of the underlying time series (can be empty if not initialized)

Definition at line 303 of file signals.h.

◆ getTimeSeriesRaw()

TimeSeries* corbo::TimeSeriesSignal::getTimeSeriesRaw ( )
inline

Raw access to the underlying time series object (returns null if not initialized)

Definition at line 300 of file signals.h.

◆ getType()

SignalType corbo::TimeSeriesSignal::getType ( ) const
inlineoverridevirtual

Get the signal type according to enumeration SignalType.

Implements corbo::SignalInterface.

Definition at line 263 of file signals.h.

◆ getValueLabels()

void corbo::TimeSeriesSignal::getValueLabels ( std::vector< std::string > &  sublabels) const
inlineoverridevirtual

Return labels for the underlying components of the signal (e.g. axes labels)

Reimplemented from corbo::SignalInterface.

Definition at line 266 of file signals.h.

◆ isEmpty()

bool corbo::TimeSeriesSignal::isEmpty ( ) const
inline

Check if the time series is empty.

Definition at line 260 of file signals.h.

◆ set() [1/2]

void corbo::TimeSeriesSignal::set ( TimeSeries::Ptr  time_series)
inline

Set time series (and override any existing)

Definition at line 279 of file signals.h.

◆ set() [2/2]

void corbo::TimeSeriesSignal::set ( const Eigen::Ref< const Eigen::VectorXd > &  time,
const Eigen::Ref< const Eigen::MatrixXd > &  values_matrix,
double  time_from_start = 0.0 
)

Set time vector and values matrix.

Any existing values are being replaced. Columns of the values_matrix correspond to vector values at a specific time instance, and hence it is values_matrix: [TimeSeries::getValueDimension() x TimeSeries::getTimeDimension()]

Parameters
[in]timeVector of all time instances [timeDimension() x 1]
[in]values_matrixMatrix containing all values w.r.t. time [TimeSeries::getValueDimension() x TimeSeries::getTimeDimension()]
[in]time_from_startSpecify an offset for all time values for post-processing
Returns
true if setting was successful, otherwise false.

Definition at line 86 of file signals.cpp.

◆ setTimeFromStart()

void corbo::TimeSeriesSignal::setTimeFromStart ( double  time_from_start)

Set time from start (offset to all time stamps in time())

Definition at line 93 of file signals.cpp.

Member Data Documentation

◆ _time_series

TimeSeries::Ptr corbo::TimeSeriesSignal::_time_series
private

Definition at line 313 of file signals.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:03