ros2_control - kilted
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 explicit LoanedStateInterface(StateInterface::ConstSharedPtr state_interface)
34 : LoanedStateInterface(state_interface, nullptr)
35 {
36 }
37
38 explicit LoanedStateInterface(StateInterface::ConstSharedPtr state_interface, Deleter && deleter)
39 : state_interface_(*state_interface), deleter_(std::forward<Deleter>(deleter))
40 {
41 }
42
43 LoanedStateInterface(const LoanedStateInterface & other) = delete;
44
46
47 virtual ~LoanedStateInterface()
48 {
49 auto logger = rclcpp::get_logger(state_interface_.get_name());
50 RCLCPP_WARN_EXPRESSION(
51 logger,
52 (get_value_statistics_.failed_counter > 0 || get_value_statistics_.timeout_counter > 0),
53 "LoanedStateInterface %s has %u (%.4f %%) timeouts and %u (%.4f %%) missed calls out of %u "
54 "get_value calls",
55 state_interface_.get_name().c_str(), get_value_statistics_.timeout_counter,
56 (get_value_statistics_.timeout_counter * 100.0) / get_value_statistics_.total_counter,
57 get_value_statistics_.failed_counter,
58 (get_value_statistics_.failed_counter * 100.0) / get_value_statistics_.total_counter,
59 get_value_statistics_.total_counter);
60 if (deleter_)
61 {
62 deleter_();
63 }
64 }
65
66 const std::string & get_name() const { return state_interface_.get_name(); }
67
68 const std::string & get_interface_name() const { return state_interface_.get_interface_name(); }
69
70 const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); }
71
72 [[deprecated(
73 "Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
74 "removed by the ROS 2 Lyrical Luth release.")]]
75 double get_value() const
76 {
77 std::optional<double> opt_value = get_optional();
78 if (opt_value.has_value())
79 {
80 return opt_value.value();
81 }
82 else
83 {
84 return std::numeric_limits<double>::quiet_NaN();
85 }
86 }
87
102 template <typename T = double>
103 [[nodiscard]] std::optional<T> get_optional(unsigned int max_tries = 10) const
104 {
105 unsigned int nr_tries = 0;
106 do
107 {
108 ++get_value_statistics_.total_counter;
109 const std::optional<T> data = state_interface_.get_optional<T>();
110 if (data.has_value())
111 {
112 return data;
113 }
114 ++get_value_statistics_.failed_counter;
115 ++nr_tries;
116 std::this_thread::yield();
117 } while (nr_tries < max_tries);
118
119 ++get_value_statistics_.timeout_counter;
120 return std::nullopt;
121 }
122
127 HandleDataType get_data_type() const { return state_interface_.get_data_type(); }
128
133 bool is_castable_to_double() const { return state_interface_.is_castable_to_double(); }
134
135protected:
136 const StateInterface & state_interface_;
137 Deleter deleter_;
138
139private:
140 struct HandleRTStatistics
141 {
142 unsigned int total_counter = 0;
143 unsigned int failed_counter = 0;
144 unsigned int timeout_counter = 0;
145 };
146 mutable HandleRTStatistics get_value_statistics_;
147};
148
149} // namespace hardware_interface
150#endif // HARDWARE_INTERFACE__LOANED_STATE_INTERFACE_HPP_
Definition hardware_info.hpp:143
bool is_castable_to_double() const
Returns true if the handle data type can be casted to double.
Definition handle.hpp:509
std::optional< T > get_optional() const
Get the value of the handle.
Definition handle.hpp:307
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:103
HandleDataType get_data_type() const
Get the data type of the state interface.
Definition loaned_state_interface.hpp:127
bool is_castable_to_double() const
Check if the state interface can be casted to double.
Definition loaned_state_interface.hpp:133
Definition handle.hpp:639
Definition actuator.hpp:22