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