scenario_simulator_v2 C++ API
configurable_rate_updater.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__CONFIGURABLE_RATE_UPDATER_HPP
16 #define TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__CONFIGURABLE_RATE_UPDATER_HPP
17 
18 #include <functional>
19 #include <rclcpp/rclcpp.hpp>
20 
21 namespace traffic_simulator
22 {
24 {
25 public:
26  template <typename NodePointer>
27  ConfigurableRateUpdater(const NodePointer & node, std::function<void()> thunk)
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))
32  {
33  }
34 
35  auto startTimer(const double update_rate) -> void;
36 
37  auto resetTimer(const double update_rate) -> void;
38 
39  auto getUpdateRate() const -> double { return update_rate_; }
40 
41 private:
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_;
45 
46  rclcpp::TimerBase::SharedPtr timer_{nullptr};
47  const std::function<void()> thunk_;
48  double update_rate_ = 0.0;
49 };
50 } // namespace traffic_simulator
51 
52 #endif // TRAFFIC_SIMULATOR__TRAFFIC_LIGHTS__CONFIGURABLE_RATE_UPDATER_HPP
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
Definition: cache.hpp:27
Definition: api.hpp:48