Loading [MathJax]/extensions/tex2jax.js
ros2_control - humble
All Classes Namespaces Functions Variables Typedefs Enumerations Pages
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
32namespace hardware_interface
33{
34
35using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
36
38
82class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
83{
84public:
86 : lifecycle_state_(
87 rclcpp_lifecycle::State(
88 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
89 {
90 }
91
93
97 ActuatorInterface(const ActuatorInterface & other) = delete;
98
99 ActuatorInterface(ActuatorInterface && other) = default;
100
101 virtual ~ActuatorInterface() = default;
102
104
109 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
110 {
111 info_ = hardware_info;
112 return CallbackReturn::SUCCESS;
113 };
114
116
124 virtual std::vector<StateInterface> export_state_interfaces() = 0;
125
127
135 virtual std::vector<CommandInterface> export_command_interfaces() = 0;
136
138
150 virtual return_type prepare_command_mode_switch(
151 const std::vector<std::string> & /*start_interfaces*/,
152 const std::vector<std::string> & /*stop_interfaces*/)
153 {
154 return return_type::OK;
155 }
156
157 // Perform switching to the new command interface.
169 virtual return_type perform_command_mode_switch(
170 const std::vector<std::string> & /*start_interfaces*/,
171 const std::vector<std::string> & /*stop_interfaces*/)
172 {
173 return return_type::OK;
174 }
175
177
186 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
187
189
197 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
198
200
203 virtual std::string get_name() const { return info_.name; }
204
206
209 const rclcpp_lifecycle::State & get_state() const { return lifecycle_state_; }
210
212
215 void set_state(const rclcpp_lifecycle::State & new_state) { lifecycle_state_ = new_state; }
216
217protected:
218 HardwareInfo info_;
219 rclcpp_lifecycle::State lifecycle_state_;
220};
221
222} // namespace hardware_interface
223#endif // HARDWARE_INTERFACE__ACTUATOR_INTERFACE_HPP_
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition actuator_interface.hpp:83
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:109
virtual std::vector< CommandInterface > export_command_interfaces()=0
Exports all command interfaces for this hardware interface.
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 actuator_interface.hpp:203
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:209
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:215
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:150
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition actuator_interface.hpp:169
Definition actuator.hpp:31
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