ros2_control - rolling
Loading...
Searching...
No Matches
generic_system.hpp
1// Copyright (c) 2021 PickNik, Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14//
15// Author: Jafar Abdi, Denis Stogl
16
17#ifndef MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
18#define MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
19
20#include <string>
21#include <vector>
22
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"
31
32using hardware_interface::return_type;
33
34namespace mock_components
35{
36using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
37
38static constexpr size_t POSITION_INTERFACE_INDEX = 0;
39static constexpr size_t VELOCITY_INTERFACE_INDEX = 1;
40static constexpr size_t ACCELERATION_INTERFACE_INDEX = 2;
41
43{
44public:
45 CallbackReturn on_init(
47
48 std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
49
50 std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
51
53 const std::vector<std::string> & start_interfaces,
54 const std::vector<std::string> & stop_interfaces) override;
55
57 const std::vector<std::string> & start_interfaces,
58 const std::vector<std::string> & stop_interfaces) override;
59
60 return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;
61
62 return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
63 {
64 return return_type::OK;
65 }
66
67protected:
69
78
80 std::vector<std::vector<double>> joint_commands_;
81 std::vector<std::vector<double>> joint_states_;
82
83 std::vector<std::string> other_interfaces_;
85 std::vector<std::vector<double>> other_commands_;
86 std::vector<std::vector<double>> other_states_;
87
88 std::vector<std::string> sensor_interfaces_;
90 std::vector<std::vector<double>> sensor_mock_commands_;
91 std::vector<std::vector<double>> sensor_states_;
92
93 std::vector<std::string> gpio_interfaces_;
95 std::vector<std::vector<double>> gpio_mock_commands_;
96 std::vector<std::vector<double>> gpio_commands_;
97 std::vector<std::vector<double>> gpio_states_;
98
99private:
100 template <typename HandleType>
101 bool get_interface(
102 const std::string & name, const std::vector<std::string> & interface_list,
103 const std::string & interface_name, const size_t vector_index,
104 std::vector<std::vector<double>> & values, std::vector<HandleType> & interfaces);
105
106 void initialize_storage_vectors(
107 std::vector<std::vector<double>> & commands, std::vector<std::vector<double>> & states,
108 const std::vector<std::string> & interfaces,
109 const std::vector<hardware_interface::ComponentInfo> & component_infos);
110
111 template <typename InterfaceType>
112 bool populate_interfaces(
113 const std::vector<hardware_interface::ComponentInfo> & components,
114 std::vector<std::string> & interfaces, std::vector<std::vector<double>> & storage,
115 std::vector<InterfaceType> & target_interfaces, bool using_state_interfaces);
116
117 bool use_mock_gpio_command_interfaces_;
118 bool use_mock_sensor_command_interfaces_;
119
120 double position_state_following_offset_;
121 std::string custom_interface_with_following_offset_;
122 size_t index_custom_interface_with_following_offset_;
123
124 bool calculate_dynamics_;
125 std::vector<size_t> joint_control_mode_;
126
127 bool command_propagation_disabled_;
128};
129
131
132} // namespace mock_components
133
134#endif // MOCK_COMPONENTS__GENERIC_SYSTEM_HPP_
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:100
Definition generic_system.hpp:43
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition generic_system.cpp:217
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition generic_system.cpp:33
return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the actuator.
Definition generic_system.hpp:62
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:422
return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition generic_system.cpp:462
std::vector< std::vector< double > > joint_commands_
The size of this vector is (standard_interfaces_.size() x nr_joints)
Definition generic_system.hpp:80
const std::vector< std::string > standard_interfaces_
Use standard interfaces for joints because they are relevant for dynamic behavior.
Definition generic_system.hpp:75
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:326
std::vector< std::vector< double > > other_commands_
The size of this vector is (other_interfaces_.size() x nr_joints)
Definition generic_system.hpp:85
std::vector< std::vector< double > > sensor_mock_commands_
The size of this vector is (sensor_interfaces_.size() x nr_joints)
Definition generic_system.hpp:90
std::vector< std::vector< double > > gpio_mock_commands_
The size of this vector is (gpio_interfaces_.size() x nr_joints)
Definition generic_system.hpp:95
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition generic_system.cpp:260
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