Time Series with SE2 support. More...
#include <time_series_se2.h>

Public Types | |
| using | ConstPtr = std::shared_ptr< const TimeSeriesSE2 > |
| using | Ptr = std::shared_ptr< TimeSeriesSE2 > |
Public Types inherited from corbo::TimeSeries | |
| typedef std::shared_ptr< const TimeSeries > | ConstPtr |
| enum | Extrapolation { Extrapolation::NoExtrapolation, Extrapolation::ZeroOrderHold } |
| enum | Interpolation { Interpolation::ZeroOrderHold, Interpolation::Linear } |
| enum | Normalization { Normalization::FirstValue, Normalization::AbsoluteMaximum, Normalization::Maximum, Normalization::Mean } |
| typedef std::shared_ptr< TimeSeries > | Ptr |
| typedef Eigen::Map< const Eigen::VectorXd > | TimeVecConstMap |
| typedef Eigen::Map< Eigen::VectorXd > | TimeVecMap |
| typedef Eigen::Map< const Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > | ValuesMatConstMap |
| typedef Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > > | ValuesMatMap |
Public Member Functions | |
| void | computeMeanCwise (Eigen::Ref< Eigen::VectorXd > mean_values) override |
| Compute and return the component-wise mean values. More... | |
| double | computeMeanOverall () override |
| Compute and return the mean value of all values among all dimensions. More... | |
| bool | getValuesInterpolate (double time, Eigen::Ref< Eigen::VectorXd > values, Interpolation interpolation=Interpolation::Linear, Extrapolation extrapolate=Extrapolation::NoExtrapolation, double tolerance=1e-6) const override |
| Retrieve value vector at a desired time stamp (seconds) via interpolation. More... | |
| TimeSeriesSE2 ()=default | |
| Default constructor. More... | |
| TimeSeriesSE2 (int value_dim) | |
| Construct empty time series with a dresired value vector dimension. More... | |
Public Member Functions inherited from corbo::TimeSeries | |
| bool | add (double time, const Eigen::Ref< const Eigen::VectorXd > &values) |
| bool | add (double time, const std::vector< double > &values) |
| void | clear () |
| double | getFinalTime () const |
| const std::vector< double > & | getTime () const |
| int | getTimeDimension () const |
| const double & | getTimeFromStart () const |
| std::vector< double > & | getTimeRef () |
| TimeVecMap | getTimeVectorView () |
| TimeVecConstMap | getTimeVectorView () const |
| int | getValueDimension () const |
| const std::vector< std::string > & | getValueLabels () const |
| std::vector< std::string > & | getValueLabelsRef () |
| const std::vector< double > & | getValues () const |
| std::vector< double > | getValues (int time_idx) const |
| Eigen::Map< const Eigen::VectorXd > | getValuesMap (int time_idx) const |
| ValuesMatMap | getValuesMatrixView () |
| ValuesMatConstMap | getValuesMatrixView () const |
| std::vector< double > & | getValuesRef () |
| bool | isColumnMajor () const |
| bool | isEmpty () const |
| virtual void | normalize (Normalization norm_method, bool value_cwise=true) |
| virtual void | normalize (Normalization norm_method, int value_idx) |
| void | print (int precision=2) const |
| void | reserve (int time_dim, int value_dim) |
| bool | set (const Eigen::Ref< const Eigen::VectorXd > &time, const Eigen::Ref< const Eigen::MatrixXd > &values_matrix, double time_from_start=0.0) |
| bool | set (const std::vector< double > &time, const std::vector< Eigen::VectorXd > &values_vector, double time_from_start=0.0) |
| void | setTimeFromStart (double tfs) |
| void | setValueDimension (int value_dim) |
| TimeSeries () | |
| TimeSeries (int value_dim) | |
| virtual | ~TimeSeries () |
Additional Inherited Members | |
Protected Attributes inherited from corbo::TimeSeries | |
| std::vector< double > | _time |
| double | _time_from_start |
| int | _value_dim |
| std::vector< std::string > | _value_labels |
| std::vector< double > | _values |
Time Series with SE2 support.
A time series represents a sequence of vectors of floating point numbers associated with time stamps. A time series might also be interpreted as a discrete-time trajectory. This class extends corbo::TimeSeries to support SE2 poses. Hereby, the third state component is always treated as orientation in [-pi, pi). In particular, whenever values are retrieved by interpolation (getValuesInterpolate()), the third state is ensured to remain properly in [-pi, pi).
Note, as the first three state components define the SE2, any further auxiliary state component is treated as ordinary real number.
Definition at line 70 of file time_series_se2.h.
| using mpc_local_planner::TimeSeriesSE2::ConstPtr = std::shared_ptr<const TimeSeriesSE2> |
Definition at line 94 of file time_series_se2.h.
| using mpc_local_planner::TimeSeriesSE2::Ptr = std::shared_ptr<TimeSeriesSE2> |
Definition at line 93 of file time_series_se2.h.
|
default |
Default constructor.
|
inlineexplicit |
Construct empty time series with a dresired value vector dimension.
Definition at line 99 of file time_series_se2.h.
|
overridevirtual |
Compute and return the component-wise mean values.
| [out] | mean_values | Resulting cwise mean values [getValueDimension() x 1] (vector size must be preallocated) |
Reimplemented from corbo::TimeSeries.
Definition at line 140 of file time_series_se2.cpp.
|
overridevirtual |
Compute and return the mean value of all values among all dimensions.
Reimplemented from corbo::TimeSeries.
Definition at line 134 of file time_series_se2.cpp.
|
overridevirtual |
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] | tolerance | specify a tolerance for which two time stamps are treated equally |
time > max(time) Reimplemented from corbo::TimeSeries.
Definition at line 54 of file time_series_se2.cpp.