Go to the documentation of this file.
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>
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;
169 const std::vector<double>&
getTime()
const {
return _time; }
207 #ifdef MESSAGE_SUPPORT
208 bool toMessage(corbo::messages::TimeSeries& message)
const;
211 bool fromMessage(
const corbo::messages::TimeSeries& message, std::stringstream* issues =
nullptr);
215 void print(
int precision = 2)
const;
239 std::vector<double>
_time;
263 using Ptr = std::shared_ptr<TimeSeriesSequence>;
264 using ConstPtr = std::shared_ptr<const TimeSeriesSequence>;
293 #ifdef MESSAGE_SUPPORT
294 bool toMessage(corbo::messages::TimeSeriesSequence& message)
const;
297 bool fromMessage(
const corbo::messages::TimeSeriesSequence& message, std::stringstream* issues =
nullptr);
308 #endif // SRC_CORE_INCLUDE_CORBO_CORE_TIME_SERIES_H_
int getTimeDimension() const
Return dimension of the time vector.
Eigen::Map< const Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > ValuesMatConstMap
Interpolation
List of available interpolation methods.
void setTimeFromStart(double tfs)
Set time from start (offset to all time stamps in time())
const std::vector< TimeSeries::Ptr > & getSequence() const
Read access to the underlying sequence of time series (shared instances)
void sortByTimeFromStart()
Ascending sort of the time series objects according to their TimeSeries::timeFromStart()
virtual void normalize(Normalization norm_method, bool value_cwise=true)
Normalize values according to a specified method.
void clear()
Clear time series (except valueLabels())
Sequence of time series objects.
std::vector< double > _time
std::vector< std::string > _value_labels
label values should be empty or valueDimension()
std::shared_ptr< const TimeSeries > ConstPtr
bool add(double time, const std::vector< double > &values)
Add time and value vector pair (STL version)
const std::vector< double > & getValues() const
Read access to the complete values matrix in column-major format [getValueDimension() x getTimeDimens...
void print(int precision=2) const
Print the current time series content to console (with a desired precision for decimal numbers)
bool isColumnMajor() const
Return if the underlying raw format is in Column-Major layout.
TimeVecConstMap getTimeVectorView() const
Read access to the underlying time values in Eigen vector format [getTimeDimension() x 1].
Eigen::Map< const Eigen::VectorXd > getValuesMap(int time_idx) const
Read access to a value vector at a given time idx (< getTimeDimension) without copying.
double getFinalTime() const
Get total time duration of the trajectory (assumes that all values are sorted with ascending time)
int getValueDimension() const
Return dimension of the value vector.
bool isEmpty() const
Determine if no time series is available.
Extrapolation
List of available interpolation methods.
int getValueDimension() const
Return dimension of the value vector.
ValuesMatConstMap getValuesMatrixView() const
Read access to the complete values matrix in Eigen matrix format [getValueDimension() x getTimeDimens...
std::shared_ptr< TimeSeriesSequence > Ptr
void setValueDimension(int value_dim)
Change value dimension (warning: clears existing values)
void reserve(int time_dim, int value_dim)
Allocate memory for a given time and value vector dimension.
const std::vector< double > & getTime() const
Read access to the underlying time values [getTimeDimension() x 1].
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.
A matrix or vector expression mapping an existing array of data.
TimeSeries()
Default constructor.
virtual double computeMeanOverall()
Compute and return the mean value of all values among all dimensions.
std::shared_ptr< const TimeSeriesSequence > ConstPtr
Time Series (trajectory resp. sequence of values w.r.t. time)
friend std::ostream & operator<<(std::ostream &out, const TimeSeries &ts)
Print TimeSeries object.
bool add(TimeSeries::Ptr ts)
Add shared instance of a time series (without copying)
double _time_from_start
Speciy an offset for the time sequence _time;.
A matrix or vector expression mapping an existing expression.
Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > ValuesMatMap
virtual void computeMeanCwise(Eigen::Ref< Eigen::VectorXd > mean_values)
Compute and return the component-wise mean values.
Eigen::Map< Eigen::VectorXd > TimeVecMap
std::vector< std::string > & getValueLabelsRef()
Access (modify) value labels for each component.
Normalization
List of available normalizations.
std::vector< double > _values
value x time [column major], column: set of values corresponding to the given time idx
std::vector< TimeSeries::Ptr > _ts_sequence
void setValueDimension(int value_dim)
Change value dimension (warning: clears existing values)
std::shared_ptr< TimeSeries > Ptr
Eigen::Map< const Eigen::VectorXd > TimeVecConstMap
bool isEmpty() const
Determine if time series is empty.
const double & getTimeFromStart() const
Get time from start (offset to all time stamps in time())
const std::vector< std::string > & getValueLabels() const
Read individual value labels (non-empty if provided)
void clear()
Erase all time series.
std::vector< double > & getValuesRef()
Access to the complete values matrix in column-major format [getValueDimension() x getTimeDimension()...
std::vector< double > & getTimeRef()
Write access to the underlying time values [getTimeDimension() x 1] (warning, modify only with 100% c...
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.
int _value_dim
We enforce a unique value dimension for all internal time_series objects.
TimeSeriesSequence()
Default constructor.
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:07:06