ros2_control - jazzy
Loading...
Searching...
No Matches
loaned_command_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_COMMAND_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__LOANED_COMMAND_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"
26
27namespace hardware_interface
28{
30{
31public:
32 using Deleter = std::function<void(void)>;
33
34 [[deprecated("Replaced by the new version using shared_ptr")]] explicit LoanedCommandInterface(
35 CommandInterface & command_interface)
36 : LoanedCommandInterface(command_interface, nullptr)
37 {
38 }
39
40 [[deprecated("Replaced by the new version using shared_ptr")]] LoanedCommandInterface(
41 CommandInterface & command_interface, Deleter && deleter)
42 : command_interface_(command_interface),
43 deleter_(std::forward<Deleter>(deleter)),
44 interface_name_(command_interface.get_name())
45 {
46 }
47
48 explicit LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter)
49 : command_interface_(*command_interface),
50 interface_name_(command_interface->get_name()),
51 deleter_(std::forward<Deleter>(deleter))
52 {
53 }
54
55 LoanedCommandInterface(const LoanedCommandInterface & other) = delete;
56
58
60 {
61 auto logger = rclcpp::get_logger(interface_name_);
62 RCLCPP_WARN_EXPRESSION(
63 logger,
64 (get_value_statistics_.failed_counter > 0 || get_value_statistics_.timeout_counter > 0),
65 "LoanedCommandInterface %s has %u (%.4f %%) timeouts and %u (~ %.4f %%) missed calls out of "
66 "%u get_value calls",
67 interface_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 * 100.0) / get_value_statistics_.total_counter,
71 get_value_statistics_.total_counter);
72 RCLCPP_WARN_EXPRESSION(
73 logger,
74 (set_value_statistics_.failed_counter > 0 || set_value_statistics_.timeout_counter > 0),
75 "LoanedCommandInterface %s has %u (%.4f %%) timeouts and %u (~ %.4f %%) missed calls out of "
76 "%u set_value calls",
77 interface_name_.c_str(), set_value_statistics_.timeout_counter,
78 (set_value_statistics_.timeout_counter * 100.0) / set_value_statistics_.total_counter,
79 set_value_statistics_.failed_counter,
80 (set_value_statistics_.failed_counter * 100.0) / set_value_statistics_.total_counter,
81 set_value_statistics_.total_counter);
82 if (deleter_)
83 {
84 deleter_();
85 }
86 }
87
88 const std::string & get_name() const { return command_interface_.get_name(); }
89
90 const std::string & get_interface_name() const { return command_interface_.get_interface_name(); }
91
92 [[deprecated(
93 "Replaced by get_name method, which is semantically more correct")]] const std::string
94 get_full_name() const
95 {
96 return command_interface_.get_name();
97 }
98
99 const std::string & get_prefix_name() const { return command_interface_.get_prefix_name(); }
100
116 template <typename T>
117 [[nodiscard]] bool set_value(const T & value, unsigned int max_tries = 10)
118 {
119 unsigned int nr_tries = 0;
120 ++set_value_statistics_.total_counter;
121 while (!command_interface_.set_limited_value(value))
122 {
123 ++set_value_statistics_.failed_counter;
124 ++nr_tries;
125 if (nr_tries == max_tries)
126 {
127 ++set_value_statistics_.timeout_counter;
128 return false;
129 }
130 std::this_thread::yield();
131 }
132 return true;
133 }
134
135 [[deprecated(
136 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
137 "removed by the ROS 2 Kilted Kaiju release.")]]
138 double get_value() const
139 {
140 std::optional<double> opt_value = get_optional();
141 if (opt_value.has_value())
142 {
143 return opt_value.value();
144 }
145 else
146 {
147 return std::numeric_limits<double>::quiet_NaN();
148 }
149 }
150
165 template <typename T = double>
166 [[nodiscard]] std::optional<T> get_optional(unsigned int max_tries = 10) const
167 {
168 unsigned int nr_tries = 0;
169 do
170 {
171 ++get_value_statistics_.total_counter;
172 const std::optional<T> data = command_interface_.get_optional<T>();
173 if (data.has_value())
174 {
175 return data;
176 }
177 ++get_value_statistics_.failed_counter;
178 ++nr_tries;
179 std::this_thread::yield();
180 } while (nr_tries < max_tries);
181
182 ++get_value_statistics_.timeout_counter;
183 return std::nullopt;
184 }
185
201 template <typename T>
202 [[deprecated(
203 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
204 "removed by the ROS 2 Kilted Kaiju release.")]] [[nodiscard]] bool
205 get_value(T & value, unsigned int max_tries = 10) const
206 {
207 const auto opt_value = get_optional<T>(max_tries);
208 if (opt_value.has_value())
209 {
210 value = opt_value.value();
211 return true;
212 }
213 return false;
214 }
215
220 HandleDataType get_data_type() const { return command_interface_.get_data_type(); }
221
222protected:
223 CommandInterface & command_interface_;
224 Deleter deleter_;
225 std::string interface_name_;
226
227private:
228 struct HandleRTStatistics
229 {
230 unsigned int total_counter = 0;
231 unsigned int failed_counter = 0;
232 unsigned int timeout_counter = 0;
233 };
234 mutable HandleRTStatistics get_value_statistics_;
235 HandleRTStatistics set_value_statistics_;
236};
237
238} // namespace hardware_interface
239#endif // HARDWARE_INTERFACE__LOANED_COMMAND_INTERFACE_HPP_
Definition handle.hpp:736
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:763
Definition hardware_info.hpp:146
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:329
Definition loaned_command_interface.hpp:30
bool set_value(const T &value, unsigned int max_tries=10)
Set the value of the command interface.
Definition loaned_command_interface.hpp:117
bool get_value(T &value, unsigned int max_tries=10) const
Get the value of the command interface.
Definition loaned_command_interface.hpp:205
HandleDataType get_data_type() const
Get the data type of the command interface.
Definition loaned_command_interface.hpp:220
std::optional< T > get_optional(unsigned int max_tries=10) const
Get the value of the command interface.
Definition loaned_command_interface.hpp:166
Definition actuator.hpp:22