time_series.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_
26 #define SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_
27 
28 #include <corbo-core/types.h>
29 
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>
33 #endif
34 
35 #include <memory>
36 #include <string>
37 #include <vector>
38 
39 namespace corbo {
40 
55 {
56  public:
60  enum class Extrapolation { NoExtrapolation, ZeroOrderHold };
62  enum class Normalization { FirstValue, AbsoluteMaximum, Maximum, Mean };
63 
64  using Ptr = std::shared_ptr<TimeSeries>;
65  using ConstPtr = std::shared_ptr<const TimeSeries>;
70 
74  explicit TimeSeries(int value_dim) : _value_dim(value_dim) {}
75 
76  virtual ~TimeSeries() {}
77 
79  int getValueDimension() const { return _value_dim; }
81  int getTimeDimension() const { return (int)_time.size(); }
83  bool isEmpty() const { return _time.empty(); }
85  bool isColumnMajor() const { return true; }
86 
87  // manipulation
89  void setValueDimension(int value_dim);
91  void reserve(int time_dim, int value_dim);
92 
94  bool add(double time, const std::vector<double>& values);
96  bool add(double time, const Eigen::Ref<const Eigen::VectorXd>& values);
97 
109  bool set(const Eigen::Ref<const Eigen::VectorXd>& time, const Eigen::Ref<const Eigen::MatrixXd>& values_matrix, double time_from_start = 0.0);
110 
122  bool set(const std::vector<double>& time, const std::vector<Eigen::VectorXd>& values_vector, double time_from_start = 0.0);
123 
125  void clear();
126 
128  const std::vector<std::string>& getValueLabels() const { return _value_labels; }
130  std::vector<std::string>& getValueLabelsRef() { return _value_labels; }
131 
132  // accessors
134  std::vector<double> getValues(int time_idx) const;
137 
156  virtual bool getValuesInterpolate(double time, Eigen::Ref<Eigen::VectorXd> values, Interpolation interpolation = Interpolation::Linear,
157  Extrapolation extrapolate = Extrapolation::NoExtrapolation, double tolerance = 1e-6) const;
158 
160  const std::vector<double>& getValues() const { return _values; }
162  std::vector<double>& getValuesRef() { return _values; }
167 
169  const std::vector<double>& getTime() const { return _time; }
171  std::vector<double>& getTimeRef() { return _time; }
173  TimeVecConstMap getTimeVectorView() const { return TimeVecConstMap(_time.data(), _time.size()); }
175  TimeVecMap getTimeVectorView() { return TimeVecMap(_time.data(), _time.size()); }
176 
178  const double& getTimeFromStart() const { return _time_from_start; }
180  void setTimeFromStart(double tfs) { _time_from_start = tfs; }
181 
183  double getFinalTime() const { return _time.empty() ? 0.0 : _time.back(); }
184 
186  virtual double computeMeanOverall();
191  virtual void computeMeanCwise(Eigen::Ref<Eigen::VectorXd> mean_values);
192 
198  virtual void normalize(Normalization norm_method, bool value_cwise = true);
199 
205  virtual void normalize(Normalization norm_method, int value_idx);
206 
207 #ifdef MESSAGE_SUPPORT
208  bool toMessage(corbo::messages::TimeSeries& message) const;
211  bool fromMessage(const corbo::messages::TimeSeries& message, std::stringstream* issues = nullptr);
212 #endif
213 
215  void print(int precision = 2) const;
216 
223  friend std::ostream& operator<<(std::ostream& out, const TimeSeries& ts);
224 
225  // overloaded operators
226  // friend std::ostream& operator<<(std::ostream& os, const std::vector<double>& values) {add()}
227 
228  protected:
229  // We implement our own column-major matrix layout with std::vector<double>
230  // instead of relying on Eigens implementation Eigen::MatrixXd
231  // since we want to support a dedicated container capacity which might
232  // be larger than the current size (see std::vector::reserve).
233  // We assume that data is frequently appended/added during data recording.
234  // Indeed, Eigen provides a conservativeResize method which utilizes std::reallocate
235  // whenever columns are added in a column-major layout, but it is not guaranteed that
236  // there is enough memory capacity to avoid copies completely.
237  int _value_dim = 0; // we could infer this from values.size()/time.size() but we do not want to compute this every lookup
238  std::vector<double> _values;
239  std::vector<double> _time;
240 
241  double _time_from_start = 0.0;
242 
243  std::vector<std::string> _value_labels;
244 };
245 
261 {
262  public:
263  using Ptr = std::shared_ptr<TimeSeriesSequence>;
264  using ConstPtr = std::shared_ptr<const TimeSeriesSequence>;
265 
268 
270  explicit TimeSeriesSequence(int value_dim) : _value_dim(value_dim) {}
271 
273  int getValueDimension() const { return _value_dim; }
275  bool isEmpty() const { return _ts_sequence.empty(); }
276 
277  // manipulation
279  void setValueDimension(int value_dim);
280 
282  bool add(TimeSeries::Ptr ts);
283 
285  const std::vector<TimeSeries::Ptr>& getSequence() const { return _ts_sequence; }
286 
288  void clear();
289 
291  void sortByTimeFromStart();
292 
293 #ifdef MESSAGE_SUPPORT
294  bool toMessage(corbo::messages::TimeSeriesSequence& message) const;
297  bool fromMessage(const corbo::messages::TimeSeriesSequence& message, std::stringstream* issues = nullptr);
298 #endif
299 
300  private:
301  std::vector<TimeSeries::Ptr> _ts_sequence;
302 
303  int _value_dim = 0;
304 };
305 
306 } // namespace corbo
307 
308 #endif // SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_
virtual ~TimeSeries()
Definition: time_series.h:76
Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > ValuesMatMap
Definition: time_series.h:66
std::vector< double > _time
Definition: time_series.h:239
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)
Definition: time_series.h:54
TimeSeriesSequence(int value_dim)
Construct empty time series sequence with a desired value vector dimension.
Definition: time_series.h:270
std::vector< TimeSeries::Ptr > _ts_sequence
Definition: time_series.h:301
std::shared_ptr< const TimeSeriesSequence > ConstPtr
Definition: time_series.h:264
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
const double & getTimeFromStart() const
Get time from start (offset to all time stamps in time())
Definition: time_series.h:178
Interpolation
List of available interpolation methods.
Definition: time_series.h:58
std::vector< double > & getTimeRef()
Write access to the underlying time values [getTimeDimension() x 1] (warning, modify only with 100% c...
Definition: time_series.h:171
ValuesMatMap getValuesMatrixView()
Access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimension()...
Definition: time_series.h:166
TimeSeries()
Default constructor.
Definition: time_series.h:72
double _time_from_start
Speciy an offset for the time sequence _time;.
Definition: time_series.h:241
TimeSeries(int value_dim)
Construct empty time series with a dresired value vector dimension.
Definition: time_series.h:74
TimeVecConstMap getTimeVectorView() const
Read access to the underlying time values in Eigen vector format [getTimeDimension() x 1]...
Definition: time_series.h:173
TimeSeriesSequence()
Default constructor.
Definition: time_series.h:267
double getFinalTime() const
Get total time duration of the trajectory (assumes that all values are sorted with ascending time) ...
Definition: time_series.h:183
TimeVecMap getTimeVectorView()
Write access to the underlying time values in Eigen vector format [getTimeDimension() x 1] (warning...
Definition: time_series.h:175
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
Definition: time_series.h:68
Sequence of time series objects.
Definition: time_series.h:260
int getValueDimension() const
Return dimension of the value vector.
Definition: time_series.h:79
const std::vector< TimeSeries::Ptr > & getSequence() const
Read access to the underlying sequence of time series (shared instances)
Definition: time_series.h:285
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.
Definition: time_series.cpp:42
int getTimeDimension() const
Return dimension of the time vector.
Definition: time_series.h:81
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())
Definition: time_series.h:180
virtual void normalize(Normalization norm_method, bool value_cwise=true)
Normalize values according to a specified method.
Normalization
List of available normalizations.
Definition: time_series.h:62
ValuesMatConstMap getValuesMatrixView() const
Read access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimens...
Definition: time_series.h:164
bool add(double time, const std::vector< double > &values)
Add time and value vector pair (STL version)
Definition: time_series.cpp:48
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 ...
Definition: time_series.h:238
Eigen::Map< const Eigen::VectorXd > TimeVecConstMap
Definition: time_series.h:69
bool isEmpty() const
Determine if no time series is available.
Definition: time_series.h:275
bool isEmpty() const
Determine if time series is empty.
Definition: time_series.h:83
const std::vector< double > & getTime() const
Read access to the underlying time values [getTimeDimension() x 1].
Definition: time_series.h:169
friend std::ostream & operator<<(std::ostream &out, const TimeSeries &ts)
Print TimeSeries object.
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
const std::vector< std::string > & getValueLabels() const
Read individual value labels (non-empty if provided)
Definition: time_series.h:128
std::vector< std::string > & getValueLabelsRef()
Access (modify) value labels for each component.
Definition: time_series.h:130
std::shared_ptr< TimeSeriesSequence > Ptr
Definition: time_series.h:263
Extrapolation
List of available interpolation methods.
Definition: time_series.h:60
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)
Definition: time_series.cpp:33
const std::vector< double > & getValues() const
Read access to the complete values matrix in column-major format [getValueDimension() x getTimeDimens...
Definition: time_series.h:160
std::vector< std::string > _value_labels
label values should be empty or valueDimension()
Definition: time_series.h:243
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:64
std::shared_ptr< const TimeSeries > ConstPtr
Definition: time_series.h:65
std::vector< double > & getValuesRef()
Access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()...
Definition: time_series.h:162
int getValueDimension() const
Return dimension of the value vector.
Definition: time_series.h:273
Eigen::Map< const Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > ValuesMatConstMap
Definition: time_series.h:67
bool isColumnMajor() const
Return if the underlying raw format is in Column-Major layout.
Definition: time_series.h:85


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