ros2_control - rolling
async_components.hpp
1 // Copyright 2023 ros2_control development team
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 HARDWARE_INTERFACE__ASYNC_COMPONENTS_HPP_
16 #define HARDWARE_INTERFACE__ASYNC_COMPONENTS_HPP_
17 
18 #include <atomic>
19 #include <thread>
20 #include <variant>
21 
22 #include "hardware_interface/actuator.hpp"
23 #include "hardware_interface/sensor.hpp"
24 #include "hardware_interface/system.hpp"
25 #include "lifecycle_msgs/msg/state.hpp"
26 #include "rclcpp/time.hpp"
27 
28 namespace hardware_interface
29 {
30 
32 {
33 public:
34  explicit AsyncComponentThread(
35  unsigned int update_rate,
36  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
37  : cm_update_rate_(update_rate), clock_interface_(clock_interface)
38  {
39  }
40 
41  // Fills the internal variant with the desired component.
42  template <typename T>
43  void register_component(T * component)
44  {
45  hardware_component_ = component;
46  }
47 
48  AsyncComponentThread(const AsyncComponentThread & t) = delete;
50 
51  // Destructor, called when the component is erased from its map.
53  {
54  terminated_.store(true, std::memory_order_seq_cst);
55  if (write_and_read_.joinable())
56  {
57  write_and_read_.join();
58  }
59  }
61 
65  void activate() { write_and_read_ = std::thread(&AsyncComponentThread::write_and_read, this); }
66 
68 
74  {
75  using TimePoint = std::chrono::system_clock::time_point;
76 
77  std::visit(
78  [this](auto & component)
79  {
80  auto previous_time = clock_interface_->get_clock()->now();
81  while (!terminated_.load(std::memory_order_relaxed))
82  {
83  auto const period = std::chrono::nanoseconds(1'000'000'000 / cm_update_rate_);
84  TimePoint next_iteration_time =
85  TimePoint(std::chrono::nanoseconds(clock_interface_->get_clock()->now().nanoseconds()));
86 
87  if (
88  component->get_lifecycle_state().id() ==
89  lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
90  {
91  auto current_time = clock_interface_->get_clock()->now();
92  auto measured_period = current_time - previous_time;
93  previous_time = current_time;
94 
95  if (!first_iteration)
96  {
97  component->write(clock_interface_->get_clock()->now(), measured_period);
98  }
99  component->read(clock_interface_->get_clock()->now(), measured_period);
100  first_iteration = false;
101  }
102  next_iteration_time += period;
103  std::this_thread::sleep_until(next_iteration_time);
104  }
105  },
106  hardware_component_);
107  }
108 
109 private:
110  std::atomic<bool> terminated_{false};
111  std::variant<Actuator *, System *, Sensor *> hardware_component_;
112  std::thread write_and_read_{};
113 
114  unsigned int cm_update_rate_;
115  bool first_iteration = true;
116  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
117 };
118 
119 }; // namespace hardware_interface
120 
121 #endif // HARDWARE_INTERFACE__ASYNC_COMPONENTS_HPP_
Definition: async_components.hpp:32
void write_and_read()
Periodically execute the component's write and read methods.
Definition: async_components.hpp:73
void activate()
Creates the component's thread.
Definition: async_components.hpp:65
Definition: actuator.hpp:34