37 Actuator * component,
unsigned int update_rate,
38 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
39 : hardware_component_(component), cm_update_rate_(update_rate), clock_interface_(clock_interface)
44 System * component,
unsigned int update_rate,
45 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
46 : hardware_component_(component), cm_update_rate_(update_rate), clock_interface_(clock_interface)
51 Sensor * component,
unsigned int update_rate,
52 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
53 : hardware_component_(component), cm_update_rate_(update_rate), clock_interface_(clock_interface)
62 terminated_.store(
true, std::memory_order_seq_cst);
63 if (write_and_read_.joinable())
65 write_and_read_.join();
69 void activate() { write_and_read_ = std::thread(&AsyncComponentThread::write_and_read,
this); }
73 using TimePoint = std::chrono::system_clock::time_point;
76 [
this](
auto & component)
78 auto previous_time = clock_interface_->get_clock()->now();
79 while (!terminated_.load(std::memory_order_relaxed))
81 auto const period = std::chrono::nanoseconds(1'000'000'000 / cm_update_rate_);
82 TimePoint next_iteration_time =
83 TimePoint(std::chrono::nanoseconds(clock_interface_->get_clock()->now().nanoseconds()));
85 if (component->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
87 auto current_time = clock_interface_->get_clock()->now();
88 auto measured_period = current_time - previous_time;
89 previous_time = current_time;
94 next_iteration_time += period;
95 std::this_thread::sleep_until(next_iteration_time);
102 std::atomic<bool> terminated_{
false};
103 std::variant<Actuator *, System *, Sensor *> hardware_component_;
104 std::thread write_and_read_{};
106 unsigned int cm_update_rate_;
107 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;