17#ifndef MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
18#define MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
23#pragma GCC diagnostic push
24#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
25#include "hardware_interface/handle.hpp"
26#pragma GCC diagnostic pop
27#include "hardware_interface/hardware_info.hpp"
28#include "hardware_interface/system_interface.hpp"
29#include "hardware_interface/types/hardware_interface_return_values.hpp"
30#include "hardware_interface/types/hardware_interface_type_values.hpp"
32using hardware_interface::return_type;
34namespace mock_components
36using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
38static constexpr size_t POSITION_INTERFACE_INDEX = 0;
39static constexpr size_t VELOCITY_INTERFACE_INDEX = 1;
40static constexpr size_t ACCELERATION_INTERFACE_INDEX = 2;
48 hardware_interface::CallbackReturn on_configure(
49 const rclcpp_lifecycle::State & previous_state)
override;
51 std::vector<hardware_interface::InterfaceDescription>
55 const std::vector<std::string> & start_interfaces,
56 const std::vector<std::string> & stop_interfaces)
override;
59 const std::vector<std::string> & start_interfaces,
60 const std::vector<std::string> & stop_interfaces)
override;
62 return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
64 return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
override
66 return return_type::OK;
80 std::vector<std::string> skip_interfaces_;
83 bool populate_interfaces(
84 const std::vector<hardware_interface::ComponentInfo> & components,
85 std::vector<hardware_interface::InterfaceDescription> & command_interface_descriptions)
const;
87 bool use_mock_gpio_command_interfaces_;
88 bool use_mock_sensor_command_interfaces_;
90 double position_state_following_offset_;
91 std::string custom_interface_with_following_offset_;
93 bool calculate_dynamics_;
94 std::vector<size_t> joint_control_mode_;
96 bool command_propagation_disabled_;
99typedef GenericSystem GenericRobot;
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:67
Definition generic_system.hpp:43
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition generic_system.cpp:34
return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the hardware.
Definition generic_system.hpp:64
return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Definition generic_system.cpp:264
return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the hardware.
Definition generic_system.cpp:331
const std::vector< std::string > standard_interfaces_
Use standard interfaces for joints because they are relevant for dynamic behavior.
Definition generic_system.hpp:77
return_type prepare_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Prepare for a new command interface switch.
Definition generic_system.cpp:184
std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions() override
Definition generic_system.cpp:166
constexpr char HW_IF_EFFORT[]
Constant defining effort interface name.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface name.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition hardware_interface_type_values.hpp:21
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32