@@ -783,8 +783,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
783
783
const std::vector<hardware_interface::HardwareInfo> control_resources =
784
784
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
785
785
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0 ];
786
- rclcpp::Logger logger = rclcpp::get_logger (" test_actuator_component" );
787
- auto state = actuator_hw.initialize (dummy_actuator, logger, nullptr );
786
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
787
+ auto state =
788
+ actuator_hw.initialize (dummy_actuator, node->get_logger (), node->get_node_clock_interface ());
788
789
789
790
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
790
791
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
@@ -938,8 +939,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default)
938
939
const std::vector<hardware_interface::HardwareInfo> control_resources =
939
940
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
940
941
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0 ];
941
- rclcpp::Logger logger = rclcpp::get_logger (" test_sensor_component" );
942
- auto state = sensor_hw.initialize (voltage_sensor_res, logger, nullptr );
942
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
943
+ auto state =
944
+ sensor_hw.initialize (voltage_sensor_res, node->get_logger (), node->get_node_clock_interface ());
943
945
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
944
946
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
945
947
@@ -1110,8 +1112,9 @@ TEST(TestComponentInterfaces, dummy_system_default)
1110
1112
const std::vector<hardware_interface::HardwareInfo> control_resources =
1111
1113
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1112
1114
const hardware_interface::HardwareInfo dummy_system = control_resources[0 ];
1113
- rclcpp::Logger logger = rclcpp::get_logger (" test_system_component" );
1114
- auto state = system_hw.initialize (dummy_system, logger, nullptr );
1115
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
1116
+ auto state =
1117
+ system_hw.initialize (dummy_system, node->get_logger (), node->get_node_clock_interface ());
1115
1118
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1116
1119
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1117
1120
@@ -1407,8 +1410,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
1407
1410
const std::vector<hardware_interface::HardwareInfo> control_resources =
1408
1411
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1409
1412
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0 ];
1410
- rclcpp::Logger logger = rclcpp::get_logger (" test_actuator_component" );
1411
- auto state = actuator_hw.initialize (dummy_actuator, logger, nullptr );
1413
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
1414
+ auto state =
1415
+ actuator_hw.initialize (dummy_actuator, node->get_logger (), node->get_node_clock_interface ());
1412
1416
1413
1417
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1414
1418
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
@@ -1541,8 +1545,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
1541
1545
const std::vector<hardware_interface::HardwareInfo> control_resources =
1542
1546
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1543
1547
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0 ];
1544
- rclcpp::Logger logger = rclcpp::get_logger (" test_actuator_component" );
1545
- auto state = actuator_hw.initialize (dummy_actuator, logger, nullptr );
1548
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
1549
+ auto state =
1550
+ actuator_hw.initialize (dummy_actuator, node->get_logger (), node->get_node_clock_interface ());
1546
1551
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1547
1552
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1548
1553
@@ -1678,8 +1683,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
1678
1683
const std::vector<hardware_interface::HardwareInfo> control_resources =
1679
1684
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1680
1685
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0 ];
1681
- rclcpp::Logger logger = rclcpp::get_logger (" test_sensor_component" );
1682
- auto state = sensor_hw.initialize (voltage_sensor_res, logger, nullptr );
1686
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
1687
+ auto state =
1688
+ sensor_hw.initialize (voltage_sensor_res, node->get_logger (), node->get_node_clock_interface ());
1683
1689
1684
1690
auto state_interfaces = sensor_hw.export_state_interfaces ();
1685
1691
// Updated because is is INACTIVE
@@ -1806,8 +1812,9 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
1806
1812
const std::vector<hardware_interface::HardwareInfo> control_resources =
1807
1813
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1808
1814
const hardware_interface::HardwareInfo dummy_system = control_resources[0 ];
1809
- rclcpp::Logger logger = rclcpp::get_logger (" test_system_component" );
1810
- auto state = system_hw.initialize (dummy_system, logger, nullptr );
1815
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
1816
+ auto state =
1817
+ system_hw.initialize (dummy_system, node->get_logger (), node->get_node_clock_interface ());
1811
1818
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1812
1819
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1813
1820
@@ -1945,8 +1952,9 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
1945
1952
const std::vector<hardware_interface::HardwareInfo> control_resources =
1946
1953
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1947
1954
const hardware_interface::HardwareInfo dummy_system = control_resources[0 ];
1948
- rclcpp::Logger logger = rclcpp::get_logger (" test_system_component" );
1949
- auto state = system_hw.initialize (dummy_system, logger, nullptr );
1955
+ rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(" test_system_components" );
1956
+ auto state =
1957
+ system_hw.initialize (dummy_system, node->get_logger (), node->get_node_clock_interface ());
1950
1958
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1951
1959
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1952
1960
0 commit comments