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_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
28#include "rclcpp_lifecycle/state.hpp"
30using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
67class SystemInterface :
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
71 : lifecycle_state_(rclcpp_lifecycle::State(
72 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
95 info_ = hardware_info;
96 return CallbackReturn::SUCCESS;
135 const std::vector<std::string> & ,
136 const std::vector<std::string> & )
138 return return_type::OK;
154 const std::vector<std::string> & ,
155 const std::vector<std::string> & )
157 return return_type::OK;
168 virtual return_type
read() = 0;
189 const rclcpp_lifecycle::State &
get_state()
const {
return lifecycle_state_; }
195 void set_state(
const rclcpp_lifecycle::State & new_state) { lifecycle_state_ = new_state; }
199 rclcpp_lifecycle::State lifecycle_state_;
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:68
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition system_interface.hpp:153
void set_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition system_interface.hpp:195
virtual std::string get_name() const
Get name of the actuator hardware.
Definition system_interface.hpp:183
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:93
const rclcpp_lifecycle::State & get_state() const
Get life-cycle state of the actuator hardware.
Definition system_interface.hpp:189
virtual return_type read()=0
Read the current state values from the actuator.
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:134
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.
SystemInterface(const SystemInterface &other)=delete
SensorInterface copy constructor is actively deleted.
virtual return_type write()=0
Write the current command values to the actuator.
Definition actuator.hpp:29
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:101
std::string name
Name of the hardware.
Definition hardware_info.hpp:103