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"
28 #include "hardware_interface/visibility_control.h"
30 using hardware_interface::return_type;
32 namespace mock_components
34 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
36 static constexpr
size_t POSITION_INTERFACE_INDEX = 0;
37 static constexpr
size_t VELOCITY_INTERFACE_INDEX = 1;
38 static constexpr
size_t ACCELERATION_INTERFACE_INDEX = 2;
45 std::vector<hardware_interface::StateInterface> export_state_interfaces()
override;
47 std::vector<hardware_interface::CommandInterface> export_command_interfaces()
override;
49 return_type prepare_command_mode_switch(
50 const std::vector<std::string> & start_interfaces,
51 const std::vector<std::string> & stop_interfaces)
override;
53 return_type perform_command_mode_switch(
54 const std::vector<std::string> & start_interfaces,
55 const std::vector<std::string> & stop_interfaces)
override;
57 return_type read(
const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
59 return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
override
61 return return_type::OK;
72 const std::vector<std::string> standard_interfaces_ = {
78 std::vector<std::vector<double>> joint_states_;
80 std::vector<std::string> other_interfaces_;
83 std::vector<std::vector<double>> other_states_;
85 std::vector<std::string> sensor_interfaces_;
88 std::vector<std::vector<double>> sensor_states_;
90 std::vector<std::string> gpio_interfaces_;
93 std::vector<std::vector<double>> gpio_commands_;
94 std::vector<std::vector<double>> gpio_states_;
97 template <
typename HandleType>
99 const std::string & name,
const std::vector<std::string> & interface_list,
100 const std::string & interface_name,
const size_t vector_index,
101 std::vector<std::vector<double>> & values, std::vector<HandleType> & interfaces);
103 void initialize_storage_vectors(
104 std::vector<std::vector<double>> & commands, std::vector<std::vector<double>> & states,
105 const std::vector<std::string> & interfaces,
106 const std::vector<hardware_interface::ComponentInfo> & component_infos);
108 template <
typename InterfaceType>
109 bool populate_interfaces(
110 const std::vector<hardware_interface::ComponentInfo> & components,
111 std::vector<std::string> & interfaces, std::vector<std::vector<double>> & storage,
112 std::vector<InterfaceType> & target_interfaces,
bool using_state_interfaces);
114 bool use_mock_gpio_command_interfaces_;
115 bool use_mock_sensor_command_interfaces_;
117 double position_state_following_offset_;
118 std::string custom_interface_with_following_offset_;
119 size_t index_custom_interface_with_following_offset_;
121 bool calculate_dynamics_;
122 std::vector<size_t> joint_control_mode_;
124 bool command_propagation_disabled_;
Definition: system_interface.hpp:82
Definition: generic_system.hpp:41
return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the actuator.
Definition: generic_system.hpp:59
std::vector< std::vector< double > > joint_commands_
The size of this vector is (standard_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:77
std::vector< std::vector< double > > other_commands_
The size of this vector is (other_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:82
std::vector< std::vector< double > > sensor_mock_commands_
The size of this vector is (sensor_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:87
std::vector< std::vector< double > > gpio_mock_commands_
The size of this vector is (gpio_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:92
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