25 #ifndef SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_    26 #define SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_    30 #ifdef MESSAGE_SUPPORT    31 #include <corbo-communication/messages/core/time_series.pb.h>    32 #include <corbo-communication/messages/core/time_series_sequence.pb.h>    62     enum class Normalization { FirstValue, AbsoluteMaximum, Maximum, Mean };
    64     using Ptr               = std::shared_ptr<TimeSeries>;
    65     using ConstPtr          = std::shared_ptr<const TimeSeries>;
    91     void reserve(
int time_dim, 
int value_dim);
    94     bool add(
double time, 
const std::vector<double>& values);
   122     bool set(
const std::vector<double>& time, 
const std::vector<Eigen::VectorXd>& values_vector, 
double time_from_start = 0.0);
   134     std::vector<double> 
getValues(
int time_idx) 
const;
   207 #ifdef MESSAGE_SUPPORT   215     void print(
int precision = 2) 
const;
   263     using Ptr      = std::shared_ptr<TimeSeriesSequence>;
   264     using ConstPtr = std::shared_ptr<const TimeSeriesSequence>;
   275     bool isEmpty()
 const { 
return _ts_sequence.empty(); }
   285     const std::vector<TimeSeries::Ptr>& 
getSequence()
 const { 
return _ts_sequence; }
   291     void sortByTimeFromStart();
   293 #ifdef MESSAGE_SUPPORT   308 #endif  // SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_ 
Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > ValuesMatMap
std::vector< double > _time
virtual double computeMeanOverall()
Compute and return the mean value of all values among all dimensions. 
Time Series (trajectory resp. sequence of values w.r.t. time) 
TimeSeriesSequence(int value_dim)
Construct empty time series sequence with a desired value vector dimension. 
std::vector< TimeSeries::Ptr > _ts_sequence
std::shared_ptr< const TimeSeriesSequence > ConstPtr
A matrix or vector expression mapping an existing array of data. 
const double & getTimeFromStart() const
Get time from start (offset to all time stamps in time()) 
Interpolation
List of available interpolation methods. 
std::vector< double > & getTimeRef()
Write access to the underlying time values [getTimeDimension() x 1] (warning, modify only with 100% c...
ValuesMatMap getValuesMatrixView()
Access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimension()...
TimeSeries()
Default constructor. 
double _time_from_start
Speciy an offset for the time sequence _time;. 
TimeSeries(int value_dim)
Construct empty time series with a dresired value vector dimension. 
TimeVecConstMap getTimeVectorView() const
Read access to the underlying time values in Eigen vector format [getTimeDimension() x 1]...
TimeSeriesSequence()
Default constructor. 
double getFinalTime() const
Get total time duration of the trajectory (assumes that all values are sorted with ascending time) ...
TimeVecMap getTimeVectorView()
Write access to the underlying time values in Eigen vector format [getTimeDimension() x 1] (warning...
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. 
Eigen::Map< Eigen::VectorXd > TimeVecMap
Sequence of time series objects. 
int getValueDimension() const
Return dimension of the value vector. 
const std::vector< TimeSeries::Ptr > & getSequence() const
Read access to the underlying sequence of time series (shared instances) 
void clear()
Clear time series (except valueLabels()) 
void reserve(int time_dim, int value_dim)
Allocate memory for a given time and value vector dimension. 
int getTimeDimension() const
Return dimension of the time vector. 
void print(int precision=2) const
Print the current time series content to console (with a desired precision for decimal numbers) ...
void setTimeFromStart(double tfs)
Set time from start (offset to all time stamps in time()) 
virtual void normalize(Normalization norm_method, bool value_cwise=true)
Normalize values according to a specified method. 
Normalization
List of available normalizations. 
ValuesMatConstMap getValuesMatrixView() const
Read access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimens...
bool add(double time, const std::vector< double > &values)
Add time and value vector pair (STL version) 
virtual void computeMeanCwise(Eigen::Ref< Eigen::VectorXd > mean_values)
Compute and return the component-wise mean values. 
std::vector< double > _values
value x time [column major], column: set of values corresponding to the given time idx ...
Eigen::Map< const Eigen::VectorXd > TimeVecConstMap
bool isEmpty() const
Determine if no time series is available. 
bool isEmpty() const
Determine if time series is empty. 
const std::vector< double > & getTime() const
Read access to the underlying time values [getTimeDimension() x 1]. 
friend std::ostream & operator<<(std::ostream &out, const TimeSeries &ts)
Print TimeSeries object. 
A matrix or vector expression mapping an existing expression. 
const std::vector< std::string > & getValueLabels() const
Read individual value labels (non-empty if provided) 
std::vector< std::string > & getValueLabelsRef()
Access (modify) value labels for each component. 
std::shared_ptr< TimeSeriesSequence > Ptr
Extrapolation
List of available interpolation methods. 
Eigen::Map< const Eigen::VectorXd > getValuesMap(int time_idx) const
Read access to a value vector at a given time idx (< getTimeDimension) without copying. 
void setValueDimension(int value_dim)
Change value dimension (warning: clears existing values) 
const std::vector< double > & getValues() const
Read access to the complete values matrix in column-major format [getValueDimension() x getTimeDimens...
std::vector< std::string > _value_labels
label values should be empty or valueDimension() 
std::shared_ptr< TimeSeries > Ptr
std::shared_ptr< const TimeSeries > ConstPtr
std::vector< double > & getValuesRef()
Access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()...
int getValueDimension() const
Return dimension of the value vector. 
Eigen::Map< const Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > ValuesMatConstMap
bool isColumnMajor() const
Return if the underlying raw format is in Column-Major layout.