ros2_control - rolling
Loading...
Searching...
No Matches
loaned_state_interface.hpp
1// Copyright 2020 Open Source Robotics Foundation, Inc.
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__LOANED_STATE_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__LOANED_STATE_INTERFACE_HPP_
17
18#include <functional>
19#include <limits>
20#include <string>
21#include <thread>
22#include <utility>
23
24#include "hardware_interface/handle.hpp"
25#include "rclcpp/logging.hpp"
26namespace hardware_interface
27{
29{
30public:
31 using Deleter = std::function<void(void)>;
32
33 [[deprecated("Replaced by the new version using shared_ptr")]] explicit LoanedStateInterface(
34 const StateInterface & state_interface)
35 : LoanedStateInterface(state_interface, nullptr)
36 {
37 }
38
39 [[deprecated("Replaced by the new version using shared_ptr")]] LoanedStateInterface(
40 const StateInterface & state_interface, Deleter && deleter)
41 : state_interface_(state_interface), deleter_(std::forward<Deleter>(deleter))
42 {
43 }
44
45 explicit LoanedStateInterface(StateInterface::ConstSharedPtr state_interface)
46 : LoanedStateInterface(state_interface, nullptr)
47 {
48 }
49
50 LoanedStateInterface(StateInterface::ConstSharedPtr state_interface, Deleter && deleter)
51 : state_interface_(*state_interface), deleter_(std::forward<Deleter>(deleter))
52 {
53 }
54
55 LoanedStateInterface(const LoanedStateInterface & other) = delete;
56
58
59 virtual ~LoanedStateInterface()
60 {
61 auto logger = rclcpp::get_logger(state_interface_.get_name());
62 RCLCPP_WARN_EXPRESSION(
63 logger,
64 (get_value_statistics_.failed_counter > 0 || get_value_statistics_.timeout_counter > 0),
65 "LoanedStateInterface %s has %u (%.4f %%) timeouts and %u (%.4f %%) missed calls out of %u "
66 "get_value calls",
67 state_interface_.get_name().c_str(), get_value_statistics_.timeout_counter,
68 (get_value_statistics_.timeout_counter * 100.0) / get_value_statistics_.total_counter,
69 get_value_statistics_.failed_counter,
70 (get_value_statistics_.failed_counter * 10.0) / get_value_statistics_.total_counter,
71 get_value_statistics_.total_counter);
72 if (deleter_)
73 {
74 deleter_();
75 }
76 }
77
78 const std::string & get_name() const { return state_interface_.get_name(); }
79
80 const std::string & get_interface_name() const { return state_interface_.get_interface_name(); }
81
82 [[deprecated(
83 "Replaced by get_name method, which is semantically more correct")]] const std::string
84 get_full_name() const
85 {
86 return state_interface_.get_name();
87 }
88
89 const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); }
90
91 [[deprecated(
92 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
93 "removed by the ROS 2 Kilted Kaiju release.")]]
94 double get_value() const
95 {
96 double value = std::numeric_limits<double>::quiet_NaN();
97 if (get_value(value))
98 {
99 return value;
100 }
101 else
102 {
103 return std::numeric_limits<double>::quiet_NaN();
104 }
105 }
106
121 template <typename T = double>
122 [[nodiscard]] std::optional<T> get_optional(unsigned int max_tries = 10) const
123 {
124 unsigned int nr_tries = 0;
125 do
126 {
127 ++get_value_statistics_.total_counter;
128 const std::optional<T> data = state_interface_.get_optional<T>();
129 if (data.has_value())
130 {
131 return data;
132 }
133 ++get_value_statistics_.failed_counter;
134 ++nr_tries;
135 std::this_thread::yield();
136 } while (nr_tries < max_tries);
137
138 ++get_value_statistics_.timeout_counter;
139 return std::nullopt;
140 }
141
157 template <typename T>
158 [[deprecated(
159 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
160 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]] bool
161 get_value(T & value, unsigned int max_tries = 10) const
162 {
163 unsigned int nr_tries = 0;
164 ++get_value_statistics_.total_counter;
165 while (!state_interface_.get_value(value))
166 {
167 ++get_value_statistics_.failed_counter;
168 ++nr_tries;
169 if (nr_tries == max_tries)
170 {
171 ++get_value_statistics_.timeout_counter;
172 return false;
173 }
174 std::this_thread::yield();
175 }
176 return true;
177 }
178
179protected:
180 const StateInterface & state_interface_;
181 Deleter deleter_;
182
183private:
184 struct HandleRTStatistics
185 {
186 unsigned int total_counter = 0;
187 unsigned int failed_counter = 0;
188 unsigned int timeout_counter = 0;
189 };
190 mutable HandleRTStatistics get_value_statistics_;
191};
192
193} // namespace hardware_interface
194#endif // HARDWARE_INTERFACE__LOANED_STATE_INTERFACE_HPP_
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:143
Definition loaned_state_interface.hpp:29
std::optional< T > get_optional(unsigned int max_tries=10) const
Get the value of the state interface.
Definition loaned_state_interface.hpp:122
bool get_value(T &value, unsigned int max_tries=10) const
Get the value of the state interface.
Definition loaned_state_interface.hpp:161
Definition handle.hpp:254
Definition actuator.hpp:33