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>
25 rclcpp::TimerBase::SharedPtr timer_ =
nullptr;
26 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
27 const rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_interface_;
28 double update_rate_ = 0.0;
29 const std::function<void()> thunk_;
30 const rclcpp::Clock::SharedPtr clock_ptr_;
33 template <
typename NodePo
inter>
35 : node_base_interface_(node->get_node_base_interface()),
36 node_timers_interface_(node->get_node_timers_interface()),
38 clock_ptr_(node->get_clock())
Definition: configurable_rate_updater.hpp:24
auto createTimer(double update_rate) -> void
Definition: configurable_rate_updater.cpp:19
auto resetUpdateRate(double update_rate) -> void
Definition: configurable_rate_updater.cpp:30
auto getUpdateRate() const -> double
Definition: configurable_rate_updater.hpp:46
ConfigurableRateUpdater(const NodePointer &node, std::function< void()> thunk)
Definition: configurable_rate_updater.hpp:34