@@ -646,6 +646,10 @@ class TestGenericSystem : public ::testing::Test
646646 </joint>
647647 </ros2_control>
648648)" ;
649+
650+ INITIALIZE_ROS2_CONTROL_INTROSPECTION_REGISTRY (
651+ node_, hardware_interface::DEFAULT_INTROSPECTION_TOPIC,
652+ hardware_interface::DEFAULT_REGISTRY_KEY);
649653 }
650654
651655 std::string hardware_system_2dof_;
@@ -669,7 +673,7 @@ class TestGenericSystem : public ::testing::Test
669673 std::string disabled_commands_;
670674 std::string hardware_system_2dof_standard_interfaces_with_same_hardware_group_;
671675 std::string hardware_system_2dof_standard_interfaces_with_two_diff_hw_groups_;
672- rclcpp::Node node_ = rclcpp::Node(" TestGenericSystem" );
676+ rclcpp::Node::SharedPtr node_ = std::make_shared< rclcpp::Node> (" TestGenericSystem" );
673677};
674678
675679// Forward declaration
@@ -694,17 +698,17 @@ class TestableResourceManager : public hardware_interface::ResourceManager
694698 FRIEND_TEST (TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio_mock_command);
695699 FRIEND_TEST (TestGenericSystem, valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True);
696700
697- explicit TestableResourceManager (rclcpp::Node & node)
701+ explicit TestableResourceManager (rclcpp::Node::SharedPtr node)
698702 : hardware_interface::ResourceManager(
699- node. get_node_clock_interface(), node. get_node_logging_interface())
703+ node-> get_node_clock_interface (), node-> get_node_logging_interface())
700704 {
701705 }
702706
703707 explicit TestableResourceManager (
704- rclcpp::Node & node, const std::string & urdf, bool activate_all = false ,
708+ rclcpp::Node::SharedPtr node, const std::string & urdf, bool activate_all = false ,
705709 unsigned int cm_update_rate = 100 )
706710 : hardware_interface::ResourceManager(
707- urdf, node. get_node_clock_interface(), node. get_node_logging_interface(), activate_all,
711+ urdf, node-> get_node_clock_interface (), node-> get_node_logging_interface(), activate_all,
708712 cm_update_rate)
709713 {
710714 }
@@ -839,7 +843,7 @@ void generic_system_functional_test(
839843 const std::string & urdf, const std::string component_name = " GenericSystem2dof" ,
840844 const double offset = 0 )
841845{
842- rclcpp::Node node (" test_generic_system" );
846+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node> (" test_generic_system" );
843847 TestableResourceManager rm (node, urdf);
844848 // check is hardware is configured
845849 auto status_map = rm.get_components_status ();
@@ -941,7 +945,7 @@ void generic_system_functional_test(
941945void generic_system_error_group_test (
942946 const std::string & urdf, const std::string component_prefix, bool validate_same_group)
943947{
944- rclcpp::Node node (" test_generic_system" );
948+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node> (" test_generic_system" );
945949 TestableResourceManager rm (node, urdf, false , 200u );
946950 const std::string component1 = component_prefix + " 1" ;
947951 const std::string component2 = component_prefix + " 2" ;
0 commit comments