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 const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); }
83
84 [[deprecated(
85 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
86 "removed by the ROS 2 Kilted Kaiju release.")]]
87 double get_value() const
88 {
89 std::optional<double> opt_value = get_optional();
90 if (opt_value.has_value())
91 {
92 return opt_value.value();
93 }
94 else
95 {
96 return std::numeric_limits<double>::quiet_NaN();
97 }
98 }
99
114 template <typename T = double>
115 [[nodiscard]] std::optional<T> get_optional(unsigned int max_tries = 10) const
116 {
117 unsigned int nr_tries = 0;
118 do
119 {
120 ++get_value_statistics_.total_counter;
121 const std::optional<T> data = state_interface_.get_optional<T>();
122 if (data.has_value())
123 {
124 return data;
125 }
126 ++get_value_statistics_.failed_counter;
127 ++nr_tries;
128 std::this_thread::yield();
129 } while (nr_tries < max_tries);
130
131 ++get_value_statistics_.timeout_counter;
132 return std::nullopt;
133 }
134
139 HandleDataType get_data_type() const { return state_interface_.get_data_type(); }
140
145 bool is_castable_to_double() const { return state_interface_.is_castable_to_double(); }
146
147protected:
148 const StateInterface & state_interface_;
149 Deleter deleter_;
150
151private:
152 struct HandleRTStatistics
153 {
154 unsigned int total_counter = 0;
155 unsigned int failed_counter = 0;
156 unsigned int timeout_counter = 0;
157 };
158 mutable HandleRTStatistics get_value_statistics_;
159};
160
161} // namespace hardware_interface
162#endif // HARDWARE_INTERFACE__LOANED_STATE_INTERFACE_HPP_
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:324
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:200
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:115
HandleDataType get_data_type() const
Get the data type of the state interface.
Definition loaned_state_interface.hpp:139
bool is_castable_to_double() const
Check if the state interface can be casted to double.
Definition loaned_state_interface.hpp:145
Definition handle.hpp:368
Definition actuator.hpp:22