ros2_control - humble
actuator_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__ACTUATOR_INTERFACE_HPP_
16 #define HARDWARE_INTERFACE__ACTUATOR_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 
69 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
70 
71 class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
72 {
73 public:
75  : lifecycle_state_(rclcpp_lifecycle::State(
76  lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
77  {
78  }
79 
81 
85  ActuatorInterface(const ActuatorInterface & other) = delete;
86 
87  ActuatorInterface(ActuatorInterface && other) = default;
88 
89  virtual ~ActuatorInterface() = default;
90 
92 
97  virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
98  {
99  info_ = hardware_info;
100  return CallbackReturn::SUCCESS;
101  };
102 
104 
112  virtual std::vector<StateInterface> export_state_interfaces() = 0;
113 
115 
123  virtual std::vector<CommandInterface> export_command_interfaces() = 0;
124 
126 
138  virtual return_type prepare_command_mode_switch(
139  const std::vector<std::string> & /*start_interfaces*/,
140  const std::vector<std::string> & /*stop_interfaces*/)
141  {
142  return return_type::OK;
143  }
144 
145  // Perform switching to the new command interface.
157  virtual return_type perform_command_mode_switch(
158  const std::vector<std::string> & /*start_interfaces*/,
159  const std::vector<std::string> & /*stop_interfaces*/)
160  {
161  return return_type::OK;
162  }
163 
165 
174  virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
175 
177 
185  virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
186 
188 
191  virtual std::string get_name() const { return info_.name; }
192 
194 
197  const rclcpp_lifecycle::State & get_state() const { return lifecycle_state_; }
198 
200 
203  void set_state(const rclcpp_lifecycle::State & new_state) { lifecycle_state_ = new_state; }
204 
205 protected:
206  HardwareInfo info_;
207  rclcpp_lifecycle::State lifecycle_state_;
208 };
209 
210 } // namespace hardware_interface
211 #endif // HARDWARE_INTERFACE__ACTUATOR_INTERFACE_HPP_
Definition: actuator_interface.hpp:72
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: actuator_interface.hpp:97
virtual std::string get_name() const
Get name of the actuator hardware.
Definition: actuator_interface.hpp:191
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
const rclcpp_lifecycle::State & get_state() const
Get life-cycle state of the actuator hardware.
Definition: actuator_interface.hpp:197
ActuatorInterface(const ActuatorInterface &other)=delete
ActuatorInterface copy constructor is actively deleted.
void set_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition: actuator_interface.hpp:203
virtual std::vector< StateInterface > export_state_interfaces()=0
Exports all state 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: actuator_interface.hpp:138
virtual std::vector< CommandInterface > export_command_interfaces()=0
Exports all command interfaces for this hardware interface.
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition: actuator_interface.hpp:157
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:106
std::string name
Name of the hardware.
Definition: hardware_info.hpp:108