75 using TimePoint = std::chrono::system_clock::time_point;
78 [
this](
auto & component)
80 auto previous_time = clock_interface_->get_clock()->now();
81 while (!terminated_.load(std::memory_order_relaxed))
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()));
88 component->get_lifecycle_state().id() ==
89 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
91 auto current_time = clock_interface_->get_clock()->now();
92 auto measured_period = current_time - previous_time;
93 previous_time = current_time;
97 component->write(clock_interface_->get_clock()->now(), measured_period);
99 component->read(clock_interface_->get_clock()->now(), measured_period);
100 first_iteration = false;
102 next_iteration_time += period;
103 std::this_thread::sleep_until(next_iteration_time);
106 hardware_component_);