Autoware.Auto
|
|
#include <reference_tracking_controller.hpp>
Classes | |
struct | SignalWithDerivative |
A Pack of both the signal and it's derivative at some time step. More... | |
Public Member Functions | |
virtual | ~ReferenceTrackerBase ()=default |
Virtual destructor. More... | |
virtual T | feedback (SignalWithDerivative reference, SignalWithDerivative observation)=0 |
T | feedback (T reference, SignalWithDerivative observation) |
T | feedback (SignalWithDerivative reference, T observation) |
T | feedback (T reference, T observation) |
Interface class for 1D reference trackers
T | A floating point type |
|
virtualdefault |
Virtual destructor.
|
pure virtual |
Primary API: given current reference and current observation (and derivatives), compute feedback control
[in] | reference | The value being tracked, sometimes referred to as y |
[in] | observation | The current observed value of the tracked value, sometimes referred to as z or o |
|
inline |
Primary API: given current reference and current observation (and derivatives), compute feedback control. Observation derivative is assumed to be zero
[in] | reference | The value being tracked, sometimes referred to as y, with derivative |
[in] | observation | The current observed value of the tracked value, sometimes referred to as z or o |
|
inline |
Primary API: given current reference and current observation (and derivatives), compute feedback control. Reference derivative is assumed to be 0
[in] | reference | The value being tracked, sometimes referred to as y |
[in] | observation | The current observed value of the tracked value, sometimes referred to as z or o, with derivative |
|
inline |
Primary API: given current reference and current observation, compute feedback control. All derivatives are assumed to be zero
[in] | reference | The value being tracked, sometimes referred to as y |
[in] | observation | The current observed value of the tracked value, sometimes referred to as z or o |