ros2_control - rolling
system_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__SYSTEM_INTERFACE_HPP_
16 #define HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "hardware_interface/handle.hpp"
23 #include "hardware_interface/hardware_info.hpp"
24 #include "hardware_interface/types/hardware_interface_return_values.hpp"
25 #include "hardware_interface/types/lifecycle_state_names.hpp"
26 #include "lifecycle_msgs/msg/state.hpp"
27 #include "rclcpp/duration.hpp"
28 #include "rclcpp/time.hpp"
29 #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
30 #include "rclcpp_lifecycle/state.hpp"
31 
32 namespace hardware_interface
33 {
35 
70 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
71 
72 class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
73 {
74 public:
76  : lifecycle_state_(rclcpp_lifecycle::State(
77  lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
78  {
79  }
80 
82 
86  SystemInterface(const SystemInterface & other) = delete;
87 
88  SystemInterface(SystemInterface && other) = default;
89 
90  virtual ~SystemInterface() = default;
91 
93 
98  virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
99  {
100  info_ = hardware_info;
101  return CallbackReturn::SUCCESS;
102  };
103 
105 
113  virtual std::vector<StateInterface> export_state_interfaces() = 0;
114 
116 
124  virtual std::vector<CommandInterface> export_command_interfaces() = 0;
125 
127 
139  virtual return_type prepare_command_mode_switch(
140  const std::vector<std::string> & /*start_interfaces*/,
141  const std::vector<std::string> & /*stop_interfaces*/)
142  {
143  return return_type::OK;
144  }
145 
146  // Perform switching to the new command interface.
158  virtual return_type perform_command_mode_switch(
159  const std::vector<std::string> & /*start_interfaces*/,
160  const std::vector<std::string> & /*stop_interfaces*/)
161  {
162  return return_type::OK;
163  }
164 
166 
175  virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
176 
178 
186  virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
187 
189 
192  virtual std::string get_name() const { return info_.name; }
193 
195 
198  const rclcpp_lifecycle::State & get_state() const { return lifecycle_state_; }
199 
201 
204  void set_state(const rclcpp_lifecycle::State & new_state) { lifecycle_state_ = new_state; }
205 
206 protected:
207  HardwareInfo info_;
208  rclcpp_lifecycle::State lifecycle_state_;
209 };
210 
211 } // namespace hardware_interface
212 #endif // HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
Definition: system_interface.hpp:73
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition: system_interface.hpp:158
void set_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition: system_interface.hpp:204
virtual std::vector< StateInterface > export_state_interfaces()=0
Exports all state interfaces for this hardware interface.
virtual std::string get_name() const
Get name of the actuator hardware.
Definition: system_interface.hpp:192
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: system_interface.hpp:98
virtual std::vector< CommandInterface > export_command_interfaces()=0
Exports all command interfaces for this hardware interface.
virtual return_type prepare_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Prepare for a new command interface switch.
Definition: system_interface.hpp:139
const rclcpp_lifecycle::State & get_state() const
Get life-cycle state of the actuator hardware.
Definition: system_interface.hpp:198
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
SystemInterface(const SystemInterface &other)=delete
SystemInterface copy constructor is actively deleted.
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
Definition: actuator.hpp:31
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:69
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:131
std::string name
Name of the hardware.
Definition: hardware_info.hpp:133