Skip to content

Commit 9801548

Browse files
committed
Fix test_component_interfaces for newly added tests
1 parent f2e8078 commit 9801548

File tree

2 files changed

+41
-22
lines changed

2 files changed

+41
-22
lines changed

hardware_interface/test/test_component_interfaces.cpp

Lines changed: 24 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -783,8 +783,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
783783
const std::vector<hardware_interface::HardwareInfo> control_resources =
784784
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
785785
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());
788789

789790
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
790791
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -938,8 +939,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default)
938939
const std::vector<hardware_interface::HardwareInfo> control_resources =
939940
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
940941
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());
943945
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
944946
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
945947

@@ -1110,8 +1112,9 @@ TEST(TestComponentInterfaces, dummy_system_default)
11101112
const std::vector<hardware_interface::HardwareInfo> control_resources =
11111113
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
11121114
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());
11151118
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
11161119
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
11171120

@@ -1407,8 +1410,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
14071410
const std::vector<hardware_interface::HardwareInfo> control_resources =
14081411
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
14091412
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());
14121416

14131417
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
14141418
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1541,8 +1545,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
15411545
const std::vector<hardware_interface::HardwareInfo> control_resources =
15421546
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
15431547
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());
15461551
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
15471552
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
15481553

@@ -1678,8 +1683,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
16781683
const std::vector<hardware_interface::HardwareInfo> control_resources =
16791684
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
16801685
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());
16831689

16841690
auto state_interfaces = sensor_hw.export_state_interfaces();
16851691
// Updated because is is INACTIVE
@@ -1806,8 +1812,9 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
18061812
const std::vector<hardware_interface::HardwareInfo> control_resources =
18071813
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
18081814
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());
18111818
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
18121819
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
18131820

@@ -1945,8 +1952,9 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
19451952
const std::vector<hardware_interface::HardwareInfo> control_resources =
19461953
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
19471954
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());
19501958
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
19511959
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
19521960

hardware_interface/test/test_component_interfaces_custom_export.cpp

Lines changed: 17 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3434
#include "hardware_interface/types/lifecycle_state_names.hpp"
3535
#include "lifecycle_msgs/msg/state.hpp"
36+
#include "rclcpp/node.hpp"
3637
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3738
#include "ros2_control_test_assets/components_urdfs.hpp"
3839
#include "ros2_control_test_assets/descriptions.hpp"
@@ -169,8 +170,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export)
169170
const std::vector<hardware_interface::HardwareInfo> control_resources =
170171
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
171172
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
172-
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component");
173-
auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr);
173+
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_component");
174+
auto state =
175+
actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface());
174176

175177
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
176178
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -234,8 +236,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export)
234236
const std::vector<hardware_interface::HardwareInfo> control_resources =
235237
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
236238
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
237-
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component");
238-
auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr);
239+
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_component");
240+
auto state =
241+
sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface());
239242
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
240243
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
241244

@@ -271,8 +274,9 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export)
271274
const std::vector<hardware_interface::HardwareInfo> control_resources =
272275
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
273276
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
274-
rclcpp::Logger logger = rclcpp::get_logger("test_system_component");
275-
auto state = system_hw.initialize(dummy_system, logger, nullptr);
277+
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_component");
278+
auto state =
279+
system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface());
276280
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
277281
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
278282

@@ -373,3 +377,10 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export)
373377
EXPECT_EQ("joint1", command_interfaces[position]->get_prefix_name());
374378
}
375379
}
380+
381+
int main(int argc, char ** argv)
382+
{
383+
rclcpp::init(argc, argv);
384+
testing::InitGoogleTest(&argc, argv);
385+
return RUN_ALL_TESTS();
386+
}

0 commit comments

Comments
 (0)