ros2_control - rolling
sensor_interface.hpp
1 // Copyright 2020 - 2021 ros2_control Development Team
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__SENSOR_INTERFACE_HPP_
16 #define HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
17 
18 #include <limits>
19 #include <memory>
20 #include <string>
21 #include <unordered_map>
22 #include <utility>
23 #include <vector>
24 
25 #include "hardware_interface/component_parser.hpp"
26 #include "hardware_interface/handle.hpp"
27 #include "hardware_interface/hardware_info.hpp"
28 #include "hardware_interface/types/hardware_interface_return_values.hpp"
29 #include "hardware_interface/types/lifecycle_state_names.hpp"
30 #include "lifecycle_msgs/msg/state.hpp"
31 #include "rclcpp/duration.hpp"
32 #include "rclcpp/logger.hpp"
33 #include "rclcpp/node_interfaces/node_clock_interface.hpp"
34 #include "rclcpp/time.hpp"
35 #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
36 #include "rclcpp_lifecycle/state.hpp"
37 #include "realtime_tools/async_function_handler.hpp"
38 
39 namespace hardware_interface
40 {
42 
76 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
77 
78 class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
79 {
80 public:
82  : lifecycle_state_(rclcpp_lifecycle::State(
83  lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
84  sensor_logger_(rclcpp::get_logger("sensor_interface"))
85  {
86  }
87 
89 
93  SensorInterface(const SensorInterface & other) = delete;
94 
95  SensorInterface(SensorInterface && other) = default;
96 
97  virtual ~SensorInterface() = default;
98 
101 
109  const HardwareInfo & hardware_info, rclcpp::Logger logger,
110  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
111  {
112  clock_interface_ = clock_interface;
113  sensor_logger_ = logger.get_child("hardware_component.sensor." + hardware_info.name);
114  info_ = hardware_info;
115  if (info_.is_async)
116  {
117  RCLCPP_INFO_STREAM(
118  get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
119  read_async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
120  read_async_handler_->init(
121  std::bind(&SensorInterface::read, this, std::placeholders::_1, std::placeholders::_2),
122  info_.thread_priority);
123  read_async_handler_->start_thread();
124  }
125  return on_init(hardware_info);
126  };
127 
129 
134  virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
135  {
136  info_ = hardware_info;
137  parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
138  parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
139  return CallbackReturn::SUCCESS;
140  };
141 
143 
154  [[deprecated(
155  "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
156  "Exporting is handled "
157  "by the Framework.")]] virtual std::vector<StateInterface>
159  {
160  // return empty vector by default. For backward compatibility we try calling
161  // export_state_interfaces() and only when empty vector is returned call
162  // on_export_state_interfaces()
163  return {};
164  }
165 
172  virtual std::vector<hardware_interface::InterfaceDescription>
174  {
175  // return empty vector by default.
176  return {};
177  }
178 
186  virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
187  {
188  // import the unlisted interfaces
189  std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
191 
192  std::vector<StateInterface::ConstSharedPtr> state_interfaces;
193  state_interfaces.reserve(
194  unlisted_interface_descriptions.size() + sensor_state_interfaces_.size() +
195  joint_state_interfaces_.size());
196 
197  // add InterfaceDescriptions and create StateInterfaces from the descriptions and add to maps.
198  for (const auto & description : unlisted_interface_descriptions)
199  {
200  auto name = description.get_name();
201  unlisted_state_interfaces_.insert(std::make_pair(name, description));
202  auto state_interface = std::make_shared<StateInterface>(description);
203  sensor_states_map_.insert(std::make_pair(name, state_interface));
204  unlisted_states_.push_back(state_interface);
205  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
206  }
207 
208  for (const auto & [name, descr] : sensor_state_interfaces_)
209  {
210  // TODO(Manuel) check for duplicates otherwise only the first appearance of "name" is inserted
211  auto state_interface = std::make_shared<StateInterface>(descr);
212  sensor_states_map_.insert(std::make_pair(name, state_interface));
213  sensor_states_.push_back(state_interface);
214  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
215  }
216 
217  for (const auto & [name, descr] : joint_state_interfaces_)
218  {
219  auto state_interface = std::make_shared<StateInterface>(descr);
220  sensor_states_map_.insert(std::make_pair(name, state_interface));
221  joint_states_.push_back(state_interface);
222  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
223  }
224 
225  return state_interfaces;
226  }
227 
229 
238  return_type trigger_read(const rclcpp::Time & time, const rclcpp::Duration & period)
239  {
240  return_type result = return_type::ERROR;
241  if (info_.is_async)
242  {
243  bool trigger_status = true;
244  std::tie(trigger_status, result) = read_async_handler_->trigger_async_callback(time, period);
245  if (!trigger_status)
246  {
247  RCLCPP_WARN(
248  get_logger(),
249  "Trigger read called while read async handler is still in progress for hardware "
250  "interface : '%s'. Failed to trigger read cycle!",
251  info_.name.c_str());
252  return return_type::OK;
253  }
254  }
255  else
256  {
257  result = read(time, period);
258  }
259  return result;
260  }
261 
263 
272  virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
273 
275 
278  virtual std::string get_name() const { return info_.name; }
279 
281 
284  virtual std::string get_group_name() const { return info_.group; }
285 
287 
290  const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
291 
293 
296  void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
297  {
298  lifecycle_state_ = new_state;
299  }
300 
301  void set_state(const std::string & interface_name, const double & value)
302  {
303  sensor_states_map_.at(interface_name)->set_value(value);
304  }
305 
306  double get_state(const std::string & interface_name) const
307  {
308  return sensor_states_map_.at(interface_name)->get_value();
309  }
310 
312 
315  rclcpp::Logger get_logger() const { return sensor_logger_; }
316 
318 
321  rclcpp::Clock::SharedPtr get_clock() const { return clock_interface_->get_clock(); }
322 
324 
327  const HardwareInfo & get_hardware_info() const { return info_; }
328 
329 protected:
330  HardwareInfo info_;
331  // interface names to InterfaceDescription
332  std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
333  std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
334  std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
335 
336  // Exported Command- and StateInterfaces in order they are listed in the hardware description.
337  std::vector<StateInterface::SharedPtr> joint_states_;
338  std::vector<StateInterface::SharedPtr> sensor_states_;
339  std::vector<StateInterface::SharedPtr> unlisted_states_;
340 
341  rclcpp_lifecycle::State lifecycle_state_;
342  std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> read_async_handler_;
343 
344 private:
345  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
346  rclcpp::Logger sensor_logger_;
347  // interface names to Handle accessed through getters/setters
348  std::unordered_map<std::string, StateInterface::SharedPtr> sensor_states_map_;
349 };
350 
351 } // namespace hardware_interface
352 #endif // HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
Definition: sensor_interface.hpp:79
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SensorInterface.
Definition: sensor_interface.hpp:321
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition: sensor_interface.hpp:186
return_type trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition: sensor_interface.hpp:238
virtual std::string get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition: sensor_interface.hpp:284
rclcpp::Logger get_logger() const
Get the logger of the SensorInterface.
Definition: sensor_interface.hpp:315
SensorInterface(const SensorInterface &other)=delete
SensorInterface copy constructor is actively deleted.
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition: sensor_interface.hpp:290
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: sensor_interface.hpp:134
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition: sensor_interface.hpp:173
virtual std::string get_name() const
Get name of the actuator hardware.
Definition: sensor_interface.hpp:278
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition: sensor_interface.hpp:296
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition: sensor_interface.hpp:108
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SensorInterface.
Definition: sensor_interface.hpp:327
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition: sensor_interface.hpp:158
Definition: actuator.hpp:34
HARDWARE_INTERFACE_PUBLIC std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition: component_parser.cpp:998
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:76
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170
int thread_priority
Async thread priority.
Definition: hardware_info.hpp:182
std::string group
Hardware group to which the hardware belongs.
Definition: hardware_info.hpp:176
bool is_async
Component is async.
Definition: hardware_info.hpp:180
std::vector< ComponentInfo > joints
Definition: hardware_info.hpp:191
std::string name
Name of the hardware.
Definition: hardware_info.hpp:172
std::vector< ComponentInfo > sensors
Definition: hardware_info.hpp:200