15#ifndef HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
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"
70using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
72class SystemInterface :
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
76 : lifecycle_state_(rclcpp_lifecycle::State(
77 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
100 info_ = hardware_info;
101 return CallbackReturn::SUCCESS;
140 const std::vector<std::string> & ,
141 const std::vector<std::string> & )
143 return return_type::OK;
159 const std::vector<std::string> & ,
160 const std::vector<std::string> & )
162 return return_type::OK;
175 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
186 virtual return_type
write(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
198 const rclcpp_lifecycle::State &
get_state()
const {
return lifecycle_state_; }
204 void set_state(
const rclcpp_lifecycle::State & new_state) { lifecycle_state_ = new_state; }
208 rclcpp_lifecycle::State lifecycle_state_;
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::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
const rclcpp_lifecycle::State & get_state() const
Get life-cycle state of the actuator hardware.
Definition system_interface.hpp:198
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
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 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:107
std::string name
Name of the hardware.
Definition hardware_info.hpp:109