ros2_control - kilted
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 explicit LoanedCommandInterface(CommandInterface::SharedPtr command_interface)
35 : LoanedCommandInterface(command_interface, nullptr)
36 {
37 }
38
39 explicit LoanedCommandInterface(CommandInterface::SharedPtr command_interface, Deleter && deleter)
40 : command_interface_(*command_interface), deleter_(std::forward<Deleter>(deleter))
41 {
42 }
43
44 LoanedCommandInterface(const LoanedCommandInterface & other) = delete;
45
47
49 {
50 auto logger = rclcpp::get_logger(command_interface_.get_name());
51 RCLCPP_WARN_EXPRESSION(
52 rclcpp::get_logger(get_name()),
53 (get_value_statistics_.failed_counter > 0 || get_value_statistics_.timeout_counter > 0),
54 "LoanedCommandInterface %s has %u (%.4f %%) timeouts and %u (~ %.4f %%) missed calls out of "
55 "%u get_value calls",
56 get_name().c_str(), get_value_statistics_.timeout_counter,
57 (get_value_statistics_.timeout_counter * 100.0) / get_value_statistics_.total_counter,
58 get_value_statistics_.failed_counter,
59 (get_value_statistics_.failed_counter * 100.0) / get_value_statistics_.total_counter,
60 get_value_statistics_.total_counter);
61 RCLCPP_WARN_EXPRESSION(
62 rclcpp::get_logger(get_name()),
63 (set_value_statistics_.failed_counter > 0 || set_value_statistics_.timeout_counter > 0),
64 "LoanedCommandInterface %s has %u (%.4f %%) timeouts and %u (~ %.4f %%) missed calls out of "
65 "%u set_value calls",
66 get_name().c_str(), set_value_statistics_.timeout_counter,
67 (set_value_statistics_.timeout_counter * 100.0) / set_value_statistics_.total_counter,
68 set_value_statistics_.failed_counter,
69 (set_value_statistics_.failed_counter * 100.0) / set_value_statistics_.total_counter,
70 set_value_statistics_.total_counter);
71 if (deleter_)
72 {
73 deleter_();
74 }
75 }
76
77 const std::string & get_name() const { return command_interface_.get_name(); }
78
79 const std::string & get_interface_name() const { return command_interface_.get_interface_name(); }
80
81 const std::string & get_prefix_name() const { return command_interface_.get_prefix_name(); }
82
98 template <typename T>
99 [[nodiscard]] bool set_value(const T & value, unsigned int max_tries = 10)
100 {
101 unsigned int nr_tries = 0;
102 ++set_value_statistics_.total_counter;
103 while (!command_interface_.set_limited_value(value))
104 {
105 ++set_value_statistics_.failed_counter;
106 ++nr_tries;
107 if (nr_tries == max_tries)
108 {
109 ++set_value_statistics_.timeout_counter;
110 return false;
111 }
112 std::this_thread::yield();
113 }
114 return true;
115 }
116
117 [[deprecated(
118 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
119 "removed by the ROS 2 Lyrical Luth release.")]]
120 double get_value() const
121 {
122 std::optional<double> opt_value = get_optional();
123 if (opt_value.has_value())
124 {
125 return opt_value.value();
126 }
127 else
128 {
129 return std::numeric_limits<double>::quiet_NaN();
130 }
131 }
132
147 template <typename T = double>
148 [[nodiscard]] std::optional<T> get_optional(unsigned int max_tries = 10) const
149 {
150 unsigned int nr_tries = 0;
151 do
152 {
153 ++get_value_statistics_.total_counter;
154 const std::optional<T> data = command_interface_.get_optional<T>();
155 if (data.has_value())
156 {
157 return data;
158 }
159 ++get_value_statistics_.failed_counter;
160 ++nr_tries;
161 std::this_thread::yield();
162 } while (nr_tries < max_tries);
163
164 ++get_value_statistics_.timeout_counter;
165 return std::nullopt;
166 }
167
172 HandleDataType get_data_type() const { return command_interface_.get_data_type(); }
173
178 bool is_castable_to_double() const { return command_interface_.is_castable_to_double(); }
179
180protected:
181 CommandInterface & command_interface_;
182 Deleter deleter_;
183
184private:
185 struct HandleRTStatistics
186 {
187 unsigned int total_counter = 0;
188 unsigned int failed_counter = 0;
189 unsigned int timeout_counter = 0;
190 };
191 mutable HandleRTStatistics get_value_statistics_;
192 HandleRTStatistics set_value_statistics_;
193};
194
195} // namespace hardware_interface
196#endif // HARDWARE_INTERFACE__LOANED_COMMAND_INTERFACE_HPP_
Definition handle.hpp:404
bool set_limited_value(const T &value)
A setter for the value of the command interface that triggers the limiter.
Definition handle.hpp:431
Definition hardware_info.hpp:137
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:314
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:183
Definition loaned_command_interface.hpp:30
bool is_castable_to_double() const
Check if the state interface can be casted to double.
Definition loaned_command_interface.hpp:178
bool set_value(const T &value, unsigned int max_tries=10)
Set the value of the command interface.
Definition loaned_command_interface.hpp:99
HandleDataType get_data_type() const
Get the data type of the command interface.
Definition loaned_command_interface.hpp:172
std::optional< T > get_optional(unsigned int max_tries=10) const
Get the value of the command interface.
Definition loaned_command_interface.hpp:148
Definition actuator.hpp:22