ros2_control - iron
Loading...
Searching...
No Matches
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/duration.hpp"
27#include "rclcpp/node.hpp"
28#include "rclcpp/time.hpp"
29
30namespace hardware_interface
31{
32
34{
35public:
36 explicit AsyncComponentThread(
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)
40 {
41 }
42
43 explicit AsyncComponentThread(
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)
47 {
48 }
49
50 explicit AsyncComponentThread(
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)
54 {
55 }
56
59
61 {
62 terminated_.store(true, std::memory_order_seq_cst);
63 if (write_and_read_.joinable())
64 {
65 write_and_read_.join();
66 }
67 }
68
69 void activate() { write_and_read_ = std::thread(&AsyncComponentThread::write_and_read, this); }
70
71 void write_and_read()
72 {
73 using TimePoint = std::chrono::system_clock::time_point;
74
75 std::visit(
76 [this](auto & component)
77 {
78 auto previous_time = clock_interface_->get_clock()->now();
79 while (!terminated_.load(std::memory_order_relaxed))
80 {
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()));
84
85 if (component->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
86 {
87 auto current_time = clock_interface_->get_clock()->now();
88 auto measured_period = current_time - previous_time;
89 previous_time = current_time;
90
91 // write
92 // read
93 }
94 next_iteration_time += period;
95 std::this_thread::sleep_until(next_iteration_time);
96 }
97 },
98 hardware_component_);
99 }
100
101private:
102 std::atomic<bool> terminated_{false};
103 std::variant<Actuator *, System *, Sensor *> hardware_component_;
104 std::thread write_and_read_{};
105
106 unsigned int cm_update_rate_;
107 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
108};
109
110}; // namespace hardware_interface
111
112#endif // HARDWARE_INTERFACE__ASYNC_COMPONENTS_HPP_
Definition actuator.hpp:35
Definition async_components.hpp:34
Definition sensor.hpp:36
Definition system.hpp:36
Definition actuator.hpp:31