15 #ifndef TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__CONFIGURABLE_RATE_UPDATER_HPP
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__CONFIGURABLE_RATE_UPDATER_HPP
19 #include <rclcpp/rclcpp.hpp>
26 template <
typename NodePo
inter>
28 : node_base_interface_(node->get_node_base_interface()),
29 node_timers_interface_(node->get_node_timers_interface()),
30 clock_ptr_(node->get_clock()),
31 thunk_(
std::move(thunk))
35 auto startTimer(
const double update_rate) -> void;
37 auto resetTimer(
const double update_rate) -> void;
42 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
43 const rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_interface_;
44 const rclcpp::Clock::SharedPtr clock_ptr_;
46 rclcpp::TimerBase::SharedPtr timer_{
nullptr};
47 const std::function<void()> thunk_;
48 double update_rate_ = 0.0;
Definition: configurable_rate_updater.hpp:24
auto startTimer(const double update_rate) -> void
Definition: configurable_rate_updater.cpp:20
auto getUpdateRate() const -> double
Definition: configurable_rate_updater.hpp:39
auto resetTimer(const double update_rate) -> void
Definition: configurable_rate_updater.cpp:30
ConfigurableRateUpdater(const NodePointer &node, std::function< void()> thunk)
Definition: configurable_rate_updater.hpp:27