reference_trajectory.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_REFERENCE_TRAJECTORY_H_
26 #define SRC_CORE_INCLUDE_CORBO_CORE_REFERENCE_TRAJECTORY_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/signals.h>
30 #include <corbo-core/time.h>
31 #include <corbo-core/time_series.h>
32 #include <corbo-core/types.h>
33 
34 #ifdef MESSAGE_SUPPORT
35 #include <corbo-communication/messages/core/reference_trajectories.pb.h>
36 #endif
37 
38 #include <memory>
39 
40 namespace corbo {
41 
60 class ReferenceTrajectoryInterface
61 {
62  public:
63  using Ptr = std::shared_ptr<ReferenceTrajectoryInterface>;
64  using OutputVector = Eigen::VectorXd;
65 
66  virtual Ptr getInstance() const = 0;
67 
68  virtual ~ReferenceTrajectoryInterface() = default;
69 
71  static Factory<ReferenceTrajectoryInterface>& getFactory() { return Factory<ReferenceTrajectoryInterface>::instance(); }
72 
73  virtual bool isStatic() const = 0;
74  virtual bool isZero() const { return false; }
75  virtual int getDimension() const = 0;
76 
77  virtual void precompute(double dt, int n, Time t) = 0;
78  virtual void precompute(const std::vector<double>& dt, Time t) = 0;
79 
80  virtual void getReference(const Time& t, OutputVector& ref) const = 0;
81 
82  virtual const OutputVector& getReferenceCached(int k) const = 0;
83 
84  virtual const OutputVector& getNextSteadyState(const Time& t) = 0;
85 
86  virtual bool isCached(double dt, int n, Time t) const = 0;
87  virtual bool isCached(const std::vector<double>& dt, Time t) const = 0;
88 
89 #ifdef MESSAGE_SUPPORT
90  virtual void toMessage(corbo::messages::ReferenceTrajectory& message) const {}
93  virtual void fromMessage(const corbo::messages::ReferenceTrajectory& message, std::stringstream* issues = nullptr) {}
94 #endif
95 };
96 
97 using ReferenceTrajectoryFactory = Factory<ReferenceTrajectoryInterface>;
98 #define FACTORY_REGISTER_REFERENCE_TRAJECTORY(type) FACTORY_REGISTER_OBJECT(type, ReferenceTrajectoryInterface)
99 
112 class StaticReference : public ReferenceTrajectoryInterface
113 {
114  public:
115  using Ptr = std::shared_ptr<StaticReference>;
116 
117  StaticReference() {}
118  explicit StaticReference(const Eigen::Ref<const OutputVector>& ref) : _ref(ref) {}
119 
120  ReferenceTrajectoryInterface::Ptr getInstance() const override { return std::make_shared<StaticReference>(); }
121 
122  bool isStatic() const override { return true; }
123  bool isZero() const override { return _ref.isZero(); }
124  int getDimension() const override { return (int)_ref.rows(); }
125 
126  void precompute(double /*dt*/, int /*n*/, Time /*t*/) override {}
127  void precompute(const std::vector<double>& /*dt*/, Time /*t*/) override {}
128 
129  void getReference(const Time& /*t*/, OutputVector& ref) const override { ref = _ref; }
130 
131  const OutputVector& getReferenceCached(int /*k*/) const override { return _ref; }
132 
133  const OutputVector& getNextSteadyState(const Time& t) override { return _ref; }
134 
135  void setReference(const Eigen::Ref<const OutputVector>& ref) { _ref = ref; }
136 
137  bool isCached(double /*dt*/, int /*n*/, Time /*t*/) const override { return true; }
138  bool isCached(const std::vector<double>& /*dt*/, Time /*t*/) const override { return true; }
139 
140 // import / export support
141 #ifdef MESSAGE_SUPPORT
142  void toMessage(corbo::messages::ReferenceTrajectory& message) const override;
143  void fromMessage(const corbo::messages::ReferenceTrajectory& message, std::stringstream* issues = nullptr) override;
144 #endif
145 
146  private:
148 };
150 
151 
162 class ZeroReference : public StaticReference
163 {
164  public:
165  using Ptr = std::shared_ptr<ZeroReference>;
166 
167  ZeroReference() {}
168  explicit ZeroReference(int dimension) : StaticReference(Eigen::VectorXd::Zero(dimension)) {}
169 
170  ReferenceTrajectoryInterface::Ptr getInstance() const override { return std::make_shared<ZeroReference>(); }
171 
172  bool isZero() const override { return true; }
173 
174  void setDimension(int dimension) { setReference(Eigen::VectorXd::Zero(dimension)); }
175 
176 #ifdef MESSAGE_SUPPORT
177  // import / export support
178  void toMessage(corbo::messages::ReferenceTrajectory& message) const override;
179  void fromMessage(const corbo::messages::ReferenceTrajectory& message, std::stringstream* issues = nullptr) override;
180 #endif
181 };
183 
184 
195 {
196  public:
197  using Ptr = std::shared_ptr<SineReferenceTrajectory>;
198 
200  explicit SineReferenceTrajectory(const double& amplitude, const double& omega, const double offset)
201  : _amplitude(amplitude), _omega(omega), _offset(offset)
202  {
203  // Initialize the cached trajectory with the FIRST trajectory point
204  _cached_trajectory.resize(1);
205  Time t(0);
206  getReference(t, _cached_trajectory[0]);
207  }
208 
209  ReferenceTrajectoryInterface::Ptr getInstance() const override { return std::make_shared<SineReferenceTrajectory>(); }
210 
211  bool isStatic() const override { return false; }
212  bool isZero() const override { return false; }
213  int getDimension() const override { return 1; }
214 
215  bool isCached(double dt, int n, Time t) const override
216  {
217  if (_cached_dt.empty() || dt != _cached_dt[0] || n != _cached_trajectory.size() || t != _cached_t) return false;
218  return true;
219  }
220 
221  bool isCached(const std::vector<double>& dt, Time t) const override
222  {
223  if (_cached_dt.empty() || dt.size() != _cached_dt.size() || t != _cached_t) return false;
224  for (int i = 0; i < dt.size(); ++i)
225  {
226  if (std::abs(dt[i] - _cached_dt[i]) < 1e-15) return false; // TODO(roesmann): floating point comparison?
227  }
228  return true;
229  }
230 
231  void precompute(double dt, int n, Time t) override
232  {
233  _cached_trajectory.resize(n);
234 
236 
237  for (int i = 0; i < n; ++i)
238  {
239  d.fromSec(dt * double(i));
240  getReference(t + d, _cached_trajectory[i]);
241  }
242  _cached_dt.resize(1);
243  _cached_dt[0] = dt;
244  _cached_t = t;
245  }
246 
247  void precompute(const std::vector<double>& dt, Time t) override
248  {
249  _cached_trajectory.resize(dt.size() + 1);
250 
251  Duration d;
252 
253  getReference(t, _cached_trajectory[0]);
254  for (int i = 0; i < dt.size(); ++i)
255  {
256  d.fromSec(dt[i]);
257  getReference(t + d, _cached_trajectory[i + 1]);
258  }
259  _cached_dt = dt;
260  _cached_t = t;
261  }
262 
263  void getReference(const Time& t, OutputVector& ref) const override
264  {
265  ref.resize(1);
266  ref(0) = _amplitude * std::sin(_omega * t.toSec() + _offset);
267  }
268 
269  const OutputVector& getReferenceCached(int k) const override
270  {
271  if (k >= _cached_trajectory.size())
272  {
273  PRINT_ERROR("SineReferenceTrajectory::getReferenceCached: k is not a valid index for cached reference. Returning zero value");
274  return _zero_vector;
275  }
276 
277  return _cached_trajectory.at(k);
278  }
279 
280  const OutputVector& getNextSteadyState(const Time& t) override
281  {
282  PRINT_ERROR_ONCE("SineReferenceTrajectory: No steady state in periodic reference. Returning zero value.");
283 
284  return _zero_vector;
285  }
286 
287  void setParameters(const double& amplitude, const double& omega, const double offset)
288  {
289  _amplitude = amplitude;
290  _omega = omega;
291  _offset = offset;
292  }
293 
294  private:
295  double _amplitude = 1;
296  double _omega = 1;
297  double _offset = 0;
298  std::vector<OutputVector> _cached_trajectory;
299  std::vector<double> _cached_dt;
300  Time _cached_t;
301  OutputVector _zero_vector = Eigen::VectorXd::Zero(1);
302 
303 #ifdef MESSAGE_SUPPORT
304  // import / export support
305  void toMessage(corbo::messages::ReferenceTrajectory& message) const override;
306  void fromMessage(const corbo::messages::ReferenceTrajectory& message, std::stringstream* issues = nullptr) override;
307 #endif
308 };
310 
311 
322 {
323  public:
324  using Ptr = std::shared_ptr<DiscreteTimeReferenceTrajectory>;
325 
326  DiscreteTimeReferenceTrajectory() : _trajectory(std::make_shared<TimeSeries>()) {}
327  explicit DiscreteTimeReferenceTrajectory(TimeSeries::Ptr trajectory, TimeSeries::Interpolation interpolation) : _interpolation(interpolation)
328  {
329  setTrajectory(trajectory);
330  }
331 
332  ReferenceTrajectoryInterface::Ptr getInstance() const override { return std::make_shared<DiscreteTimeReferenceTrajectory>(); }
333 
334  bool isStatic() const override { return _trajectory && _trajectory->getTimeDimension() == 1; }
335  bool isZero() const override
336  {
337  if (!_trajectory || _trajectory->getValueDimension() == 0) return false;
338 
339  return std::all_of(_trajectory->getValues().begin(), _trajectory->getValues().end(), [](double i) { return (i < 1e-9 && i > -1e-9); });
340  }
341  int getDimension() const override { return _trajectory ? _trajectory->getValueDimension() : 0; }
342 
343  bool isCached(double dt, int n, Time t) const override
344  {
345  if (_cached_dt.empty() || dt != _cached_dt[0] || n != _cached_trajectory.size() || t != _cached_t) return false;
346  return true;
347  }
348 
349  bool isCached(const std::vector<double>& dt, Time t) const override
350  {
351  if (_cached_dt.empty() || dt.size() != _cached_dt.size() || t != _cached_t) return false;
352  for (int i = 0; i < dt.size(); ++i)
353  {
354  if (std::abs(dt[i] - _cached_dt[i]) < 1e-15) return false; // TODO(roesmann): floating point comparison?
355  }
356  return true;
357  }
358 
359  void precompute(double dt, int n, Time t) override
360  {
361  _cached_trajectory.resize(n);
362 
364 
365  for (int i = 0; i < n; ++i)
366  {
367  d.fromSec(dt * double(i));
368  getReference(t + d, _cached_trajectory[i]);
369  }
370  _cached_dt.resize(1);
371  _cached_dt[0] = dt;
372  _cached_t = t;
373  }
374 
375  void precompute(const std::vector<double>& dt, Time t) override
376  {
377  _cached_trajectory.resize(dt.size() + 1);
378 
379  Duration d;
380 
381  getReference(t, _cached_trajectory[0]);
382  for (int i = 0; i < dt.size(); ++i)
383  {
384  d.fromSec(dt[i]);
385  getReference(t + d, _cached_trajectory[i + 1]);
386  }
387  _cached_dt = dt;
388  _cached_t = t;
389  }
390 
391  void getReference(const Time& t, OutputVector& ref) const override
392  {
393  if (!_trajectory || _trajectory->getValueDimension() == 0)
394  {
395  PRINT_ERROR("DiscreteTimeReferenceTrajectory: trajectory is empty.");
396  return;
397  }
398 
399  double time = t.toSec() - _trajectory->getTimeFromStart();
400 
401  ref.resize(_trajectory->getValueDimension());
402 
403  if (time <= 0 || _trajectory->getTimeDimension() ==
404  1) // TODO(roesmann): should we really check for time <= 0? do we also need to take time_from_start into account?
405  ref = _trajectory->getValuesMap(0);
406  else if (time >= _trajectory->getFinalTime())
407  ref = _trajectory->getValuesMap(_trajectory->getTimeDimension() - 1);
408  else
409  _trajectory->getValuesInterpolate(time, ref, _interpolation, TimeSeries::Extrapolation::ZeroOrderHold);
410  }
411 
412  const OutputVector& getReferenceCached(int k) const override
413  {
414  if (k >= _cached_trajectory.size())
415  {
416  PRINT_ERROR(
417  "DiscreteTimeReferenceTrajectory::getReferenceCached: k is not a valid index for cached reference. Returning next steady state");
418  return _next_steady_state;
419  }
420 
421  return _cached_trajectory[k];
422  }
423 
424  const OutputVector& getNextSteadyState(const Time& t) override { return _next_steady_state; }
425 
426  void setTrajectory(TimeSeries::Ptr trajectory, TimeSeries::Interpolation interpolation)
427  {
428  setTrajectory(trajectory);
429  _interpolation = interpolation;
430  }
431 
432  void setTrajectory(TimeSeries::Ptr trajectory)
433  {
434  if (!trajectory || trajectory->getValueDimension() == 0)
435  {
436  PRINT_ERROR("DiscreteTimeReferenceTrajectory must be initialized with at least one point in trajectory");
437  return;
438  }
439 
440  _trajectory = trajectory;
441  _next_steady_state = trajectory->getValuesMap(trajectory->getTimeDimension() - 1);
442 
443  // Initialize the cached trajectory with the FIRST trajectory point
444  _cached_trajectory.resize(1);
445  _cached_trajectory[0] = trajectory->getValuesMap(0);
446  }
447 
448  void setTimeFromStart(const Time& time_from_start)
449  {
450  if (_trajectory) _trajectory->setTimeFromStart(time_from_start.toSec());
451  }
452 
453  void setInterpolationMethod(TimeSeries::Interpolation interpolation) { _interpolation = interpolation; }
454 
455  const TimeSeries::Ptr& getReferenceTrajectory() { return _trajectory; }
456 
457 #ifdef MESSAGE_SUPPORT
458  // import / export support
459  void toMessage(corbo::messages::ReferenceTrajectory& message) const override;
460  void fromMessage(const corbo::messages::ReferenceTrajectory& message, std::stringstream* issues = nullptr) override;
461 #endif
462 
463  private:
464  TimeSeries::Ptr _trajectory;
465  std::vector<OutputVector> _cached_trajectory;
466  std::vector<double> _cached_dt;
467  Time _cached_t;
468  OutputVector _next_steady_state;
470 };
472 
473 
484 {
485  public:
486  using Ptr = std::shared_ptr<BlindDiscreteTimeReferenceTrajectory>;
487 
490  {
491  setTrajectory(trajectory);
492  }
493 
494  ReferenceTrajectoryInterface::Ptr getInstance() const override { return std::make_shared<BlindDiscreteTimeReferenceTrajectory>(); }
495 
496  bool isStatic() const override { return _trajectory && _trajectory->getTimeDimension() == 1; }
497  bool isZero() const override
498  {
499  if (!_trajectory || _trajectory->getValueDimension() == 0) return false;
500 
501  return std::all_of(_trajectory->getValues().begin(), _trajectory->getValues().end(), [](double i) { return (i < 1e-9 && i > -1e-9); });
502  }
503  int getDimension() const override { return _trajectory ? _trajectory->getValueDimension() : 0; }
504 
505  bool isCached(double dt, int n, Time t) const override
506  {
507  if (_output_cache.size() != getDimension() || t != _cached_t) return false;
508  return true;
509  }
510 
511  bool isCached(const std::vector<double>& dt, Time t) const override
512  {
513  if (_output_cache.size() != getDimension() || t != _cached_t) return false;
514  return true;
515  }
516 
517  void precompute(double dt, int n, Time t) override
518  {
520  _cached_t = t;
521  }
522 
523  void precompute(const std::vector<double>& dt, Time t) override
524  {
526  _cached_t = t;
527  }
528 
529  void getReference(const Time& t, OutputVector& ref) const override
530  {
531  if (!_trajectory || _trajectory->getValueDimension() == 0)
532  {
533  PRINT_ERROR("BlindDiscreteTimeReferenceTrajectory: trajectory is empty.");
534  return;
535  }
536 
537  double time = t.toSec() - _trajectory->getTimeFromStart();
538 
539  ref.resize(_trajectory->getValueDimension());
540 
541  if (time <= 0 || _trajectory->getTimeDimension() == 1)
542  ref = _trajectory->getValuesMap(0);
543  else if (time >= _trajectory->getFinalTime())
544  ref = _trajectory->getValuesMap(_trajectory->getTimeDimension() - 1);
545  else
546  _trajectory->getValuesInterpolate(time, ref, _interpolation, TimeSeries::Extrapolation::ZeroOrderHold);
547  }
548 
549  const OutputVector& getReferenceCached(int k) const override { return _output_cache; }
550 
551  const OutputVector& getNextSteadyState(const Time& t) override { return _next_steady_state; }
552 
553  void setTrajectory(TimeSeries::Ptr trajectory, TimeSeries::Interpolation interpolation)
554  {
555  setTrajectory(trajectory);
556  _interpolation = interpolation;
557  }
558 
559  void setTrajectory(TimeSeries::Ptr trajectory)
560  {
561  if (!trajectory || trajectory->getValueDimension() == 0)
562  {
563  PRINT_ERROR("BlindDiscreteTimeReferenceTrajectory must be initialized with at least one point in trajectory");
564  return;
565  }
566 
567  _trajectory = trajectory;
568  _next_steady_state = trajectory->getValuesMap(trajectory->getTimeDimension() - 1);
569  }
570 
571  void setTimeFromStart(const Time& time_from_start)
572  {
573  if (_trajectory) _trajectory->setTimeFromStart(time_from_start.toSec());
574  }
575 
576  void setInterpolationMethod(TimeSeries::Interpolation interpolation) { _interpolation = interpolation; }
577 
579 
580 #ifdef MESSAGE_SUPPORT
581  // import / export support
582  void toMessage(corbo::messages::ReferenceTrajectory& message) const override;
583  void fromMessage(const corbo::messages::ReferenceTrajectory& message, std::stringstream* issues = nullptr) override;
584 #endif
585 
586  private:
589  Time _cached_t;
592 };
594 
595 } // namespace corbo
596 
597 #endif // SRC_CORE_INCLUDE_CORBO_CORE_REFERENCE_TRAJECTORY_H_
corbo::TimeSeries::Interpolation
Interpolation
List of available interpolation methods.
Definition: time_series.h:102
corbo::Duration::fromSec
void fromSec(double t)
Set duration from seconds (see Duration(double t))
Definition: time.h:162
corbo::BlindDiscreteTimeReferenceTrajectory::getReferenceTrajectory
const TimeSeries::Ptr & getReferenceTrajectory()
Definition: reference_trajectory.h:600
sin
const EIGEN_DEVICE_FUNC SinReturnType sin() const
Definition: ArrayCwiseUnaryOps.h:220
corbo::ReferenceTrajectoryInterface::isStatic
virtual bool isStatic() const =0
corbo::ReferenceTrajectoryInterface::getInstance
virtual Ptr getInstance() const =0
factory.h
corbo::ReferenceTrajectoryInterface
Interface class for reference trajectories.
Definition: reference_trajectory.h:82
corbo::BlindDiscreteTimeReferenceTrajectory::_cached_t
Time _cached_t
Definition: reference_trajectory.h:611
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::StaticReference::StaticReference
StaticReference()
Definition: reference_trajectory.h:139
corbo::ReferenceTrajectoryInterface::getReferenceCached
virtual const OutputVector & getReferenceCached(int k) const =0
corbo::BlindDiscreteTimeReferenceTrajectory::getDimension
int getDimension() const override
Definition: reference_trajectory.h:525
corbo::BlindDiscreteTimeReferenceTrajectory::BlindDiscreteTimeReferenceTrajectory
BlindDiscreteTimeReferenceTrajectory()
Definition: reference_trajectory.h:510
corbo::BlindDiscreteTimeReferenceTrajectory::setTimeFromStart
void setTimeFromStart(const Time &time_from_start)
Definition: reference_trajectory.h:593
corbo::StaticReference
Static reference trajectory.
Definition: reference_trajectory.h:134
corbo::BlindDiscreteTimeReferenceTrajectory::isCached
bool isCached(double dt, int n, Time t) const override
Definition: reference_trajectory.h:527
corbo::ReferenceTrajectoryInterface::isZero
virtual bool isZero() const
Definition: reference_trajectory.h:118
corbo::StaticReference::getReference
void getReference(const Time &, OutputVector &ref) const override
Definition: reference_trajectory.h:151
corbo::ReferenceTrajectoryInterface::~ReferenceTrajectoryInterface
virtual ~ReferenceTrajectoryInterface()=default
corbo::ReferenceTrajectoryFactory
Factory< ReferenceTrajectoryInterface > ReferenceTrajectoryFactory
Definition: reference_trajectory.h:119
corbo::BlindDiscreteTimeReferenceTrajectory::_trajectory
TimeSeries::Ptr _trajectory
Definition: reference_trajectory.h:609
corbo::StaticReference::getDimension
int getDimension() const override
Definition: reference_trajectory.h:146
PRINT_ERROR_ONCE
#define PRINT_ERROR_ONCE(msg)
Print msg-stream only once.
Definition: console.h:176
abs
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE AbsReturnType abs() const
Definition: ArrayCwiseUnaryOps.h:43
corbo::BlindDiscreteTimeReferenceTrajectory::setTrajectory
void setTrajectory(TimeSeries::Ptr trajectory, TimeSeries::Interpolation interpolation)
Definition: reference_trajectory.h:575
corbo::ReferenceTrajectoryInterface::getNextSteadyState
virtual const OutputVector & getNextSteadyState(const Time &t)=0
corbo::ReferenceTrajectoryInterface::isCached
virtual bool isCached(double dt, int n, Time t) const =0
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
corbo::BlindDiscreteTimeReferenceTrajectory
discrete time reference trajectory in which the precompute step is not aware of the trajectory
Definition: reference_trajectory.h:505
corbo::Time::toSec
double toSec() const
Cast time stamp to seconds.
Definition: time.h:303
corbo::StaticReference::isCached
bool isCached(double, int, Time) const override
Definition: reference_trajectory.h:159
corbo::DiscreteTimeReferenceTrajectory
discrete time reference trajectory
Definition: reference_trajectory.h:343
corbo::Duration
Representation of time durations.
Definition: time.h:128
time.h
time_series.h
corbo::BlindDiscreteTimeReferenceTrajectory::precompute
void precompute(double dt, int n, Time t) override
Definition: reference_trajectory.h:539
corbo::StaticReference::getReferenceCached
const OutputVector & getReferenceCached(int) const override
Definition: reference_trajectory.h:153
corbo::StaticReference::isZero
bool isZero() const override
Definition: reference_trajectory.h:145
corbo::BlindDiscreteTimeReferenceTrajectory::isStatic
bool isStatic() const override
Definition: reference_trajectory.h:518
corbo::BlindDiscreteTimeReferenceTrajectory::getReferenceCached
const OutputVector & getReferenceCached(int k) const override
Definition: reference_trajectory.h:571
signals.h
corbo::ReferenceTrajectoryInterface::Ptr
std::shared_ptr< ReferenceTrajectoryInterface > Ptr
Definition: reference_trajectory.h:107
corbo::TimeSeries::Interpolation::ZeroOrderHold
@ ZeroOrderHold
corbo::ReferenceTrajectoryInterface::getFactory
static Factory< ReferenceTrajectoryInterface > & getFactory()
Get access to the associated factory.
Definition: reference_trajectory.h:115
corbo::ReferenceTrajectoryInterface::getReference
virtual void getReference(const Time &t, OutputVector &ref) const =0
corbo::ReferenceTrajectoryInterface::getDimension
virtual int getDimension() const =0
corbo::SineReferenceTrajectory
Sine reference trajectory.
Definition: reference_trajectory.h:216
corbo::TimeSeries
Time Series (trajectory resp. sequence of values w.r.t. time)
Definition: time_series.h:76
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::StaticReference::_ref
OutputVector _ref
Definition: reference_trajectory.h:169
corbo::StaticReference::isStatic
bool isStatic() const override
Definition: reference_trajectory.h:144
corbo::StaticReference::precompute
void precompute(double, int, Time) override
Definition: reference_trajectory.h:148
corbo::ZeroReference
Zero reference trajectory.
Definition: reference_trajectory.h:184
std
Definition: Half.h:150
corbo::StaticReference::getInstance
ReferenceTrajectoryInterface::Ptr getInstance() const override
Definition: reference_trajectory.h:142
types.h
corbo::Time
Representation of time stamps.
Definition: time.h:273
corbo::BlindDiscreteTimeReferenceTrajectory::setInterpolationMethod
void setInterpolationMethod(TimeSeries::Interpolation interpolation)
Definition: reference_trajectory.h:598
corbo::BlindDiscreteTimeReferenceTrajectory::_interpolation
TimeSeries::Interpolation _interpolation
Definition: reference_trajectory.h:613
corbo::BlindDiscreteTimeReferenceTrajectory::getReference
void getReference(const Time &t, OutputVector &ref) const override
Definition: reference_trajectory.h:551
corbo::BlindDiscreteTimeReferenceTrajectory::_output_cache
OutputVector _output_cache
Definition: reference_trajectory.h:610
corbo::StaticReference::setReference
void setReference(const Eigen::Ref< const OutputVector > &ref)
Definition: reference_trajectory.h:157
corbo::BlindDiscreteTimeReferenceTrajectory::_next_steady_state
OutputVector _next_steady_state
Definition: reference_trajectory.h:612
FACTORY_REGISTER_REFERENCE_TRAJECTORY
#define FACTORY_REGISTER_REFERENCE_TRAJECTORY(type)
Definition: reference_trajectory.h:120
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::ReferenceTrajectoryInterface::OutputVector
Eigen::VectorXd OutputVector
Definition: reference_trajectory.h:108
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::TimeSeries::Extrapolation::ZeroOrderHold
@ ZeroOrderHold
corbo::BlindDiscreteTimeReferenceTrajectory::isZero
bool isZero() const override
Definition: reference_trajectory.h:519
PRINT_ERROR
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173
corbo::BlindDiscreteTimeReferenceTrajectory::getInstance
ReferenceTrajectoryInterface::Ptr getInstance() const override
Definition: reference_trajectory.h:516
corbo::BlindDiscreteTimeReferenceTrajectory::getNextSteadyState
const OutputVector & getNextSteadyState(const Time &t) override
Definition: reference_trajectory.h:573
corbo::ReferenceTrajectoryInterface::precompute
virtual void precompute(double dt, int n, Time t)=0
corbo::StaticReference::getNextSteadyState
const OutputVector & getNextSteadyState(const Time &t) override
Definition: reference_trajectory.h:155


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:09