@@ -36,7 +36,55 @@ const double CONTROLLER_MANAGER_ALLOWED_SAMPLE_ERROR_MS = 1.0;
3636
3737namespace webots_ros2_control {
3838
39- #if HARDWARE_INTERFACE_VERSION_MAJOR >= 5 || HARDWARE_INTERFACE_VERSION_MAJOR >= 4 && HARDWARE_INTERFACE_VERSION_MINOR >= 12
39+ #if HARDWARE_INTERFACE_VERSION_MAJOR >= 5 && HARDWARE_INTERFACE_VERSION_MINOR >= 3
40+ class WebotsResourceManager : public hardware_interface ::ResourceManager {
41+ public:
42+ WebotsResourceManager (webots_ros2_driver::WebotsNode *node) :
43+ hardware_interface::ResourceManager (node->get_node_clock_interface (), node->get_node_logging_interface()),
44+ mHardwareLoader(" webots_ros2_control" , " webots_ros2_control::Ros2ControlSystemInterface" ),
45+ mLogger(node->get_logger ().get_child(" WebotsResourceManager" )) {
46+ mNode = node;
47+ }
48+
49+ WebotsResourceManager (const WebotsResourceManager &) = delete;
50+
51+ bool load_and_initialize_components (const hardware_interface::ResourceManagerParams & param) override {
52+ components_are_loaded_and_initialized_ = true ;
53+
54+ std::vector<hardware_interface::HardwareInfo> controlHardware;
55+ try {
56+ controlHardware = hardware_interface::parse_control_resources_from_urdf (param.robot_description );
57+ } catch (const std::runtime_error &ex) {
58+ throw std::runtime_error (" URDF cannot be parsed by a `ros2_control` component parser: " + std::string (ex.what ()));
59+ }
60+ for (unsigned int i = 0 ; i < controlHardware.size (); i++) {
61+ const std::string pluginName = controlHardware[i].hardware_plugin_name ;
62+
63+ std::unique_ptr<webots_ros2_control::Ros2ControlSystemInterface> webotsSystem;
64+ try {
65+ webotsSystem = std::unique_ptr<webots_ros2_control::Ros2ControlSystemInterface>(
66+ mHardwareLoader .createUnmanagedInstance (pluginName));
67+ } catch (pluginlib::PluginlibException &ex) {
68+ RCLCPP_ERROR (mLogger , " The plugin failed to load for some reason. Error: %s\n " , ex.what ());
69+ continue ;
70+ }
71+
72+ webotsSystem->init (mNode , controlHardware[i]);
73+ hardware_interface::HardwareComponentParams component_params;
74+ component_params.hardware_info = controlHardware[i];
75+ component_params.clock = mNode ->get_clock ();
76+ component_params.logger = mNode ->get_logger ();
77+ import_component (std::move (webotsSystem), component_params);
78+ }
79+
80+ return components_are_loaded_and_initialized_;
81+ }
82+ private:
83+ webots_ros2_driver::WebotsNode *mNode ;
84+ pluginlib::ClassLoader<webots_ros2_control::Ros2ControlSystemInterface> mHardwareLoader ;
85+ rclcpp::Logger mLogger ;
86+ };
87+ #elif HARDWARE_INTERFACE_VERSION_MAJOR >= 5 || HARDWARE_INTERFACE_VERSION_MAJOR >= 4 && HARDWARE_INTERFACE_VERSION_MINOR >= 12
4088 class WebotsResourceManager : public hardware_interface ::ResourceManager {
4189 public:
4290 WebotsResourceManager (webots_ros2_driver::WebotsNode *node) :
0 commit comments