17#ifndef MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
18#define MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
23#include "hardware_interface/handle.hpp"
24#include "hardware_interface/hardware_info.hpp"
25#include "hardware_interface/system_interface.hpp"
26#include "hardware_interface/types/hardware_interface_return_values.hpp"
27#include "hardware_interface/types/hardware_interface_type_values.hpp"
29using hardware_interface::return_type;
31namespace mock_components
33using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
35static constexpr size_t POSITION_INTERFACE_INDEX = 0;
36static constexpr size_t VELOCITY_INTERFACE_INDEX = 1;
37static constexpr size_t ACCELERATION_INTERFACE_INDEX = 2;
49 const std::vector<std::string> & start_interfaces,
50 const std::vector<std::string> & stop_interfaces)
override;
53 const std::vector<std::string> & start_interfaces,
54 const std::vector<std::string> & stop_interfaces)
override;
56 return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
58 return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
override
60 return return_type::OK;
77 std::vector<std::vector<double>> joint_states_;
79 std::vector<std::string> other_interfaces_;
82 std::vector<std::vector<double>> other_states_;
84 std::vector<std::string> sensor_interfaces_;
87 std::vector<std::vector<double>> sensor_states_;
89 std::vector<std::string> gpio_interfaces_;
92 std::vector<std::vector<double>> gpio_commands_;
93 std::vector<std::vector<double>> gpio_states_;
96 template <
typename HandleType>
98 const std::string & name,
const std::vector<std::string> & interface_list,
99 const std::string & interface_name,
const size_t vector_index,
100 std::vector<std::vector<double>> & values, std::vector<HandleType> & interfaces);
102 void initialize_storage_vectors(
103 std::vector<std::vector<double>> & commands, std::vector<std::vector<double>> & states,
104 const std::vector<std::string> & interfaces,
105 const std::vector<hardware_interface::ComponentInfo> & component_infos);
107 template <
typename InterfaceType>
108 bool populate_interfaces(
109 const std::vector<hardware_interface::ComponentInfo> & components,
110 std::vector<std::string> & interfaces, std::vector<std::vector<double>> & storage,
111 std::vector<InterfaceType> & target_interfaces,
bool using_state_interfaces);
113 bool use_mock_gpio_command_interfaces_;
114 bool use_mock_sensor_command_interfaces_;
116 double position_state_following_offset_;
117 std::string custom_interface_with_following_offset_;
118 size_t index_custom_interface_with_following_offset_;
120 bool calculate_dynamics_;
121 std::vector<size_t> joint_control_mode_;
123 bool command_propagation_disabled_;
Definition system_interface.hpp:83
Definition generic_system.hpp:40
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition generic_system.cpp:216
return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the actuator.
Definition generic_system.hpp:58
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:421
CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition generic_system.cpp:33
return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition generic_system.cpp:461
std::vector< std::vector< double > > joint_commands_
The size of this vector is (standard_interfaces_.size() x nr_joints)
Definition generic_system.hpp:76
const std::vector< std::string > standard_interfaces_
Use standard interfaces for joints because they are relevant for dynamic behavior.
Definition generic_system.hpp:71
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:325
std::vector< std::vector< double > > other_commands_
The size of this vector is (other_interfaces_.size() x nr_joints)
Definition generic_system.hpp:81
std::vector< std::vector< double > > sensor_mock_commands_
The size of this vector is (sensor_interfaces_.size() x nr_joints)
Definition generic_system.hpp:86
std::vector< std::vector< double > > gpio_mock_commands_
The size of this vector is (gpio_interfaces_.size() x nr_joints)
Definition generic_system.hpp:91
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition generic_system.cpp:259
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
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:170