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"
29 using hardware_interface::return_type;
31 namespace mock_components
33 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
35 static constexpr
size_t POSITION_INTERFACE_INDEX = 0;
36 static constexpr
size_t VELOCITY_INTERFACE_INDEX = 1;
37 static constexpr
size_t ACCELERATION_INTERFACE_INDEX = 2;
44 std::vector<hardware_interface::StateInterface> export_state_interfaces()
override;
46 std::vector<hardware_interface::CommandInterface> export_command_interfaces()
override;
48 return_type prepare_command_mode_switch(
49 const std::vector<std::string> & start_interfaces,
50 const std::vector<std::string> & stop_interfaces)
override;
52 return_type perform_command_mode_switch(
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;
71 const std::vector<std::string> standard_interfaces_ = {
77 std::size_t joint_index;
78 std::size_t mimicked_joint_index;
79 double multiplier = 1.0;
81 std::vector<MimicJoint> mimic_joints_;
85 std::vector<std::vector<double>> joint_states_;
87 std::vector<std::string> other_interfaces_;
90 std::vector<std::vector<double>> other_states_;
92 std::vector<std::string> sensor_interfaces_;
95 std::vector<std::vector<double>> sensor_states_;
97 std::vector<std::string> gpio_interfaces_;
100 std::vector<std::vector<double>> gpio_commands_;
101 std::vector<std::vector<double>> gpio_states_;
104 template <
typename HandleType>
106 const std::string & name,
const std::vector<std::string> & interface_list,
107 const std::string & interface_name,
const size_t vector_index,
108 std::vector<std::vector<double>> & values, std::vector<HandleType> & interfaces);
110 void initialize_storage_vectors(
111 std::vector<std::vector<double>> & commands, std::vector<std::vector<double>> & states,
112 const std::vector<std::string> & interfaces,
113 const std::vector<hardware_interface::ComponentInfo> & component_infos);
115 template <
typename InterfaceType>
116 bool populate_interfaces(
117 const std::vector<hardware_interface::ComponentInfo> & components,
118 std::vector<std::string> & interfaces, std::vector<std::vector<double>> & storage,
119 std::vector<InterfaceType> & target_interfaces,
bool using_state_interfaces);
121 bool use_mock_gpio_command_interfaces_;
122 bool use_mock_sensor_command_interfaces_;
124 double position_state_following_offset_;
125 std::string custom_interface_with_following_offset_;
126 size_t index_custom_interface_with_following_offset_;
128 bool calculate_dynamics_;
129 std::vector<size_t> joint_control_mode_;
131 bool command_propagation_disabled_;
Definition: system_interface.hpp:73
Definition: generic_system.hpp:40
return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the actuator.
Definition: generic_system.hpp:58
std::vector< std::vector< double > > joint_commands_
The size of this vector is (standard_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:84
std::vector< std::vector< double > > other_commands_
The size of this vector is (other_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:89
std::vector< std::vector< double > > sensor_mock_commands_
The size of this vector is (sensor_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:94
std::vector< std::vector< double > > gpio_mock_commands_
The size of this vector is (gpio_interfaces_.size() x nr_joints)
Definition: generic_system.hpp:99
constexpr char HW_IF_EFFORT[]
Constant defining effort interface.
Definition: hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface.
Definition: hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition: hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition: hardware_interface_type_values.hpp:21
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:106
Definition: generic_system.hpp:76