18 #ifndef REFERENCE_TRACKING_CONTROLLER__REFERENCE_TRACKING_CONTROLLER_HPP_ 19 #define REFERENCE_TRACKING_CONTROLLER__REFERENCE_TRACKING_CONTROLLER_HPP_ 23 #include <type_traits> 29 namespace reference_tracking_controller
37 std::is_floating_point<T>::value,
38 "Reference trackers only work for floating point types");
65 return feedback({reference,
T{}}, observation);
76 return feedback(reference, {observation,
T{}});
87 return feedback({reference,
T{}}, {observation,
T{}});
94 #endif // REFERENCE_TRACKING_CONTROLLER__REFERENCE_TRACKING_CONTROLLER_HPP_
T
Definition: catr_diff.py:22
T feedback(T reference, SignalWithDerivative observation)
Definition: reference_tracking_controller.hpp:63
T feedback(T reference, T observation)
Definition: reference_tracking_controller.hpp:85
#define REFERENCE_TRACKING_CONTROLLER_PUBLIC
Definition: common/reference_tracking_controller/include/reference_tracking_controller/visibility_control.hpp:44
A Pack of both the signal and it's derivative at some time step.
Definition: reference_tracking_controller.hpp:42
T derivative
Derivative or rate of signal at current time step.
Definition: reference_tracking_controller.hpp:45
T value
Value of signal at current time step.
Definition: reference_tracking_controller.hpp:44
Definition: reference_tracking_controller.hpp:34
T feedback(SignalWithDerivative reference, T observation)
Definition: reference_tracking_controller.hpp:74
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24