Time Series (trajectory resp. sequence of values w.r.t. time) More...
#include <time_series.h>
Public Types | |
using | ConstPtr = std::shared_ptr< const TimeSeries > |
enum | Extrapolation { Extrapolation::NoExtrapolation, Extrapolation::ZeroOrderHold } |
List of available interpolation methods. More... | |
enum | Interpolation { Interpolation::ZeroOrderHold, Interpolation::Linear } |
List of available interpolation methods. More... | |
enum | Normalization { Normalization::FirstValue, Normalization::AbsoluteMaximum, Normalization::Maximum, Normalization::Mean } |
List of available normalizations. More... | |
using | Ptr = std::shared_ptr< TimeSeries > |
using | TimeVecConstMap = Eigen::Map< const Eigen::VectorXd > |
using | TimeVecMap = Eigen::Map< Eigen::VectorXd > |
using | ValuesMatConstMap = Eigen::Map< const Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > |
using | ValuesMatMap = Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > |
Public Member Functions | |
bool | add (double time, const std::vector< double > &values) |
Add time and value vector pair (STL version) More... | |
bool | add (double time, const Eigen::Ref< const Eigen::VectorXd > &values) |
Add time and value vector pair (Eigen version) More... | |
void | clear () |
Clear time series (except valueLabels()) More... | |
virtual void | computeMeanCwise (Eigen::Ref< Eigen::VectorXd > mean_values) |
Compute and return the component-wise mean values. More... | |
virtual double | computeMeanOverall () |
Compute and return the mean value of all values among all dimensions. More... | |
double | getFinalTime () const |
Get total time duration of the trajectory (assumes that all values are sorted with ascending time) More... | |
const std::vector< double > & | getTime () const |
Read access to the underlying time values [getTimeDimension() x 1]. More... | |
int | getTimeDimension () const |
Return dimension of the time vector. More... | |
const double & | getTimeFromStart () const |
Get time from start (offset to all time stamps in time()) More... | |
std::vector< double > & | getTimeRef () |
Write access to the underlying time values [getTimeDimension() x 1] (warning, modify only with 100% care) More... | |
TimeVecConstMap | getTimeVectorView () const |
Read access to the underlying time values in Eigen vector format [getTimeDimension() x 1]. More... | |
TimeVecMap | getTimeVectorView () |
Write access to the underlying time values in Eigen vector format [getTimeDimension() x 1] (warning, modify only with 100% care) More... | |
int | getValueDimension () const |
Return dimension of the value vector. More... | |
const std::vector< std::string > & | getValueLabels () const |
Read individual value labels (non-empty if provided) More... | |
std::vector< std::string > & | getValueLabelsRef () |
Access (modify) value labels for each component. More... | |
std::vector< double > | getValues (int time_idx) const |
Obtain value vector (copy) at a given time idx (< getTimeDimension()) More... | |
const std::vector< double > & | getValues () const |
Read access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()]. More... | |
virtual bool | getValuesInterpolate (double time, Eigen::Ref< Eigen::VectorXd > values, Interpolation interpolation=Interpolation::Linear, Extrapolation extrapolate=Extrapolation::NoExtrapolation, double tolerance=1e-6) const |
Retrieve value vector at a desired time stamp (seconds) via interpolation. More... | |
Eigen::Map< const Eigen::VectorXd > | getValuesMap (int time_idx) const |
Read access to a value vector at a given time idx (< getTimeDimension) without copying. More... | |
ValuesMatConstMap | getValuesMatrixView () const |
Read access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimension()]. More... | |
ValuesMatMap | getValuesMatrixView () |
Access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimension()] (warning, modify only with 100% care) More... | |
std::vector< double > & | getValuesRef () |
Access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()] (warning, modify only with 100% care) More... | |
bool | isColumnMajor () const |
Return if the underlying raw format is in Column-Major layout. More... | |
bool | isEmpty () const |
Determine if time series is empty. More... | |
virtual void | normalize (Normalization norm_method, bool value_cwise=true) |
Normalize values according to a specified method. More... | |
virtual void | normalize (Normalization norm_method, int value_idx) |
Normalize a given value index according to a specified method. More... | |
void | print (int precision=2) const |
Print the current time series content to console (with a desired precision for decimal numbers) More... | |
void | reserve (int time_dim, int value_dim) |
Allocate memory for a given time and value vector dimension. More... | |
bool | 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... | |
bool | set (const std::vector< double > &time, const std::vector< Eigen::VectorXd > &values_vector, double time_from_start=0.0) |
Set time vector and values matrix (STL version) More... | |
void | setTimeFromStart (double tfs) |
Set time from start (offset to all time stamps in time()) More... | |
void | setValueDimension (int value_dim) |
Change value dimension (warning: clears existing values) More... | |
TimeSeries () | |
Default constructor. More... | |
TimeSeries (int value_dim) | |
Construct empty time series with a dresired value vector dimension. More... | |
virtual | ~TimeSeries () |
Protected Attributes | |
std::vector< double > | _time |
double | _time_from_start = 0.0 |
Speciy an offset for the time sequence _time;. More... | |
int | _value_dim = 0 |
std::vector< std::string > | _value_labels |
label values should be empty or valueDimension() More... | |
std::vector< double > | _values |
value x time [column major], column: set of values corresponding to the given time idx More... | |
Friends | |
std::ostream & | operator<< (std::ostream &out, const TimeSeries &ts) |
Print TimeSeries object. More... | |
Time Series (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.
Definition at line 54 of file time_series.h.
using corbo::TimeSeries::ConstPtr = std::shared_ptr<const TimeSeries> |
Definition at line 65 of file time_series.h.
using corbo::TimeSeries::Ptr = std::shared_ptr<TimeSeries> |
Definition at line 64 of file time_series.h.
using corbo::TimeSeries::TimeVecConstMap = Eigen::Map<const Eigen::VectorXd> |
Definition at line 69 of file time_series.h.
using corbo::TimeSeries::TimeVecMap = Eigen::Map<Eigen::VectorXd> |
Definition at line 68 of file time_series.h.
using corbo::TimeSeries::ValuesMatConstMap = Eigen::Map<const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor> > |
Definition at line 67 of file time_series.h.
using corbo::TimeSeries::ValuesMatMap = Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor> > |
Definition at line 66 of file time_series.h.
|
strong |
List of available interpolation methods.
Enumerator | |
---|---|
NoExtrapolation | |
ZeroOrderHold |
Definition at line 60 of file time_series.h.
|
strong |
List of available interpolation methods.
Enumerator | |
---|---|
ZeroOrderHold | |
Linear |
Definition at line 58 of file time_series.h.
|
strong |
List of available normalizations.
Enumerator | |
---|---|
FirstValue | |
AbsoluteMaximum | |
Maximum | |
Mean |
Definition at line 62 of file time_series.h.
|
inline |
Default constructor.
Definition at line 72 of file time_series.h.
|
inlineexplicit |
Construct empty time series with a dresired value vector dimension.
Definition at line 74 of file time_series.h.
|
inlinevirtual |
Definition at line 76 of file time_series.h.
bool corbo::TimeSeries::add | ( | double | time, |
const std::vector< double > & | values | ||
) |
Add time and value vector pair (STL version)
Definition at line 48 of file time_series.cpp.
bool corbo::TimeSeries::add | ( | double | time, |
const Eigen::Ref< const Eigen::VectorXd > & | values | ||
) |
Add time and value vector pair (Eigen version)
Definition at line 64 of file time_series.cpp.
void corbo::TimeSeries::clear | ( | ) |
Clear time series (except valueLabels())
Definition at line 144 of file time_series.cpp.
|
virtual |
Compute and return the component-wise mean values.
[out] | mean_values | Resulting cwise mean values [getValueDimension() x 1] (vector size must be preallocated) |
Definition at line 245 of file time_series.cpp.
|
virtual |
Compute and return the mean value of all values among all dimensions.
Definition at line 243 of file time_series.cpp.
|
inline |
Get total time duration of the trajectory (assumes that all values are sorted with ascending time)
Definition at line 183 of file time_series.h.
|
inline |
Read access to the underlying time values [getTimeDimension() x 1].
Definition at line 169 of file time_series.h.
|
inline |
Return dimension of the time vector.
Definition at line 81 of file time_series.h.
|
inline |
Get time from start (offset to all time stamps in time())
Definition at line 178 of file time_series.h.
|
inline |
Write access to the underlying time values [getTimeDimension() x 1] (warning, modify only with 100% care)
Definition at line 171 of file time_series.h.
|
inline |
Read access to the underlying time values in Eigen vector format [getTimeDimension() x 1].
Definition at line 173 of file time_series.h.
|
inline |
Write access to the underlying time values in Eigen vector format [getTimeDimension() x 1] (warning, modify only with 100% care)
Definition at line 175 of file time_series.h.
|
inline |
Return dimension of the value vector.
Definition at line 79 of file time_series.h.
|
inline |
Read individual value labels (non-empty if provided)
Definition at line 128 of file time_series.h.
|
inline |
Access (modify) value labels for each component.
Definition at line 130 of file time_series.h.
std::vector< double > corbo::TimeSeries::getValues | ( | int | time_idx | ) | const |
Obtain value vector (copy) at a given time idx (< getTimeDimension())
Definition at line 151 of file time_series.cpp.
|
inline |
Read access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()].
Definition at line 160 of file time_series.h.
|
virtual |
Retrieve value vector at a desired time stamp (seconds) via interpolation.
This method interpolates the underlying time series object at a desired time stamp (given in seconds). Interpolation and extrapolation settings can be passed as optional arguments.
[in] | time | desired time stamp |
[out] | values | interpolated value vector w.r.t. time |
[in] | interpolation | interpolation method according to Interpolation enum |
[in] | extrapolate | specify whether exrapliation should be applied with a similar method like interpolation |
[in] | threshold | specify a tolerance for which two time stamps are treated equally |
time
> max(time) Definition at line 168 of file time_series.cpp.
Eigen::Map< const Eigen::VectorXd > corbo::TimeSeries::getValuesMap | ( | int | time_idx | ) | const |
Read access to a value vector at a given time idx (< getTimeDimension) without copying.
Definition at line 161 of file time_series.cpp.
|
inline |
Read access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimension()].
Definition at line 164 of file time_series.h.
|
inline |
Access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimension()] (warning, modify only with 100% care)
Definition at line 166 of file time_series.h.
|
inline |
Access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()] (warning, modify only with 100% care)
Definition at line 162 of file time_series.h.
|
inline |
Return if the underlying raw format is in Column-Major layout.
Definition at line 85 of file time_series.h.
|
inline |
Determine if time series is empty.
Definition at line 83 of file time_series.h.
|
virtual |
Normalize values according to a specified method.
[in] | norm_method | Desired normalization method |
[in] | value_cwise | Specify whether the norm-method should be applied component-wise or among all dimensions at once. |
Definition at line 255 of file time_series.cpp.
|
virtual |
Normalize a given value index according to a specified method.
[in] | norm_method | Desired normalization method |
[in] | value_idx | Specy which value (value < getValueDimension()) should be normalized |
Definition at line 311 of file time_series.cpp.
void corbo::TimeSeries::print | ( | int | precision = 2 | ) | const |
Print the current time series content to console (with a desired precision for decimal numbers)
Definition at line 430 of file time_series.cpp.
Allocate memory for a given time and value vector dimension.
Definition at line 42 of file time_series.cpp.
bool corbo::TimeSeries::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: [getValueDimension() x getTimeDimension()]
[in] | time | Vector of all time instances [getTimeDimension() x 1] |
[in] | values_matrix | Matrix containing all values w.r.t. time [getValueDimension() x getTimeDimension()] |
[in] | time_from_start | Specify an offset for all time values for post-processing |
Definition at line 79 of file time_series.cpp.
bool corbo::TimeSeries::set | ( | const std::vector< double > & | time, |
const std::vector< Eigen::VectorXd > & | values_vector, | ||
double | time_from_start = 0.0 |
||
) |
Set time vector and values matrix (STL version)
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: [getValueDimension() x getTimeDimension()]
[in] | time | Vector of all time instances [getTimeDimension() x 1] |
[in] | values_vector | Vector containing all value vectors w.r.t. time |
[in] | time_from_start | Specify an offset for all time values for post-processing |
Definition at line 106 of file time_series.cpp.
|
inline |
Set time from start (offset to all time stamps in time())
Definition at line 180 of file time_series.h.
void corbo::TimeSeries::setValueDimension | ( | int | value_dim | ) |
Change value dimension (warning: clears existing values)
Definition at line 33 of file time_series.cpp.
|
friend |
Print TimeSeries object.
out | output stream |
ts | time series object to be printed |
Definition at line 432 of file time_series.cpp.
|
protected |
Definition at line 239 of file time_series.h.
|
protected |
Speciy an offset for the time sequence _time;.
Definition at line 241 of file time_series.h.
|
protected |
Definition at line 237 of file time_series.h.
|
protected |
label values should be empty or valueDimension()
Definition at line 243 of file time_series.h.
|
protected |
value x time [column major], column: set of values corresponding to the given time idx
Definition at line 238 of file time_series.h.