Skip to content

Commit 5ad795c

Browse files
committed
Update tests to use the new updated non deprecated methods
1 parent fac1e37 commit 5ad795c

File tree

3 files changed

+120
-51
lines changed

3 files changed

+120
-51
lines changed

hardware_interface/test/test_component_interfaces.cpp

Lines changed: 102 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,8 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
5656
// BEGIN (Handle export change): for backward compatibility
5757
class DummyActuator : public hardware_interface::ActuatorInterface
5858
{
59-
CallbackReturn on_init(const hardware_interface::HardwareInfo & /*info*/) override
59+
CallbackReturn on_init(
60+
const hardware_interface::HardwareComponentInterfaceParams & /*info*/) override
6061
{
6162
// We hardcode the info
6263
return CallbackReturn::SUCCESS;
@@ -169,7 +170,7 @@ class DummyActuator : public hardware_interface::ActuatorInterface
169170

170171
class DummyActuatorDefault : public hardware_interface::ActuatorInterface
171172
{
172-
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
173+
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams & info) override
173174
{
174175
// We hardcode the info
175176
if (
@@ -260,7 +261,8 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface
260261
// BEGIN (Handle export change): for backward compatibility
261262
class DummySensor : public hardware_interface::SensorInterface
262263
{
263-
CallbackReturn on_init(const hardware_interface::HardwareInfo & /*info*/) override
264+
CallbackReturn on_init(
265+
const hardware_interface::HardwareComponentInterfaceParams & /*info*/) override
264266
{
265267
// We hardcode the info
266268
return CallbackReturn::SUCCESS;
@@ -325,7 +327,7 @@ class DummySensor : public hardware_interface::SensorInterface
325327

326328
class DummySensorDefault : public hardware_interface::SensorInterface
327329
{
328-
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
330+
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams & info) override
329331
{
330332
if (
331333
hardware_interface::SensorInterface::on_init(info) !=
@@ -386,7 +388,7 @@ class DummySensorDefault : public hardware_interface::SensorInterface
386388

387389
class DummySensorJointDefault : public hardware_interface::SensorInterface
388390
{
389-
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
391+
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams & info) override
390392
{
391393
if (
392394
hardware_interface::SensorInterface::on_init(info) !=
@@ -447,7 +449,8 @@ class DummySensorJointDefault : public hardware_interface::SensorInterface
447449
// BEGIN (Handle export change): for backward compatibility
448450
class DummySystem : public hardware_interface::SystemInterface
449451
{
450-
CallbackReturn on_init(const hardware_interface::HardwareInfo & /* info */) override
452+
CallbackReturn on_init(
453+
const hardware_interface::HardwareComponentInterfaceParams & /* info */) override
451454
{
452455
// We hardcode the info
453456
return CallbackReturn::SUCCESS;
@@ -593,7 +596,7 @@ class DummySystem : public hardware_interface::SystemInterface
593596

594597
class DummySystemDefault : public hardware_interface::SystemInterface
595598
{
596-
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override
599+
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams & info) override
597600
{
598601
if (
599602
hardware_interface::SystemInterface::on_init(info) !=
@@ -702,7 +705,8 @@ class DummySystemDefault : public hardware_interface::SystemInterface
702705
class DummySystemPreparePerform : public hardware_interface::SystemInterface
703706
{
704707
// Override the pure virtual functions with default behavior
705-
CallbackReturn on_init(const hardware_interface::HardwareInfo & /* info */) override
708+
CallbackReturn on_init(
709+
const hardware_interface::HardwareComponentInterfaceParams & /* info */) override
706710
{
707711
// We hardcode the info
708712
return CallbackReturn::SUCCESS;
@@ -763,8 +767,11 @@ TEST(TestComponentInterfaces, dummy_actuator)
763767

764768
hardware_interface::HardwareInfo mock_hw_info{};
765769
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
766-
auto state =
767-
actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
770+
hardware_interface::HardwareComponentParams params;
771+
params.hardware_info = mock_hw_info;
772+
params.clock = node->get_clock();
773+
params.logger = node->get_logger();
774+
auto state = actuator_hw.initialize(params);
768775
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
769776
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
770777

@@ -865,8 +872,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
865872
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
866873
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
867874
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
868-
auto state =
869-
actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface());
875+
hardware_interface::HardwareComponentParams params;
876+
params.hardware_info = dummy_actuator;
877+
params.clock = node->get_clock();
878+
params.logger = node->get_logger();
879+
auto state = actuator_hw.initialize(params);
870880

871881
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
872882
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -987,8 +997,11 @@ TEST(TestComponentInterfaces, dummy_sensor)
987997

988998
hardware_interface::HardwareInfo mock_hw_info{};
989999
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_components");
990-
auto state =
991-
sensor_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1000+
hardware_interface::HardwareComponentParams params;
1001+
params.hardware_info = mock_hw_info;
1002+
params.clock = node->get_clock();
1003+
params.logger = node->get_logger();
1004+
auto state = sensor_hw.initialize(params);
9921005
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
9931006
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
9941007

@@ -1027,8 +1040,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default)
10271040
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
10281041
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
10291042
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1030-
auto state =
1031-
sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface());
1043+
hardware_interface::HardwareComponentParams params;
1044+
params.hardware_info = voltage_sensor_res;
1045+
params.clock = node->get_clock();
1046+
params.logger = node->get_logger();
1047+
auto state = sensor_hw.initialize(params);
10321048
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
10331049
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
10341050

@@ -1072,8 +1088,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint)
10721088
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
10731089
const hardware_interface::HardwareInfo sensor_res = control_resources[0];
10741090
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1075-
auto state =
1076-
sensor_hw.initialize(sensor_res, node->get_logger(), node->get_node_clock_interface());
1091+
hardware_interface::HardwareComponentParams params;
1092+
params.hardware_info = sensor_res;
1093+
params.clock = node->get_clock();
1094+
params.logger = node->get_logger();
1095+
auto state = sensor_hw.initialize(params);
10771096
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
10781097
ASSERT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
10791098

@@ -1121,8 +1140,11 @@ TEST(TestComponentInterfaces, dummy_system)
11211140

11221141
hardware_interface::HardwareInfo mock_hw_info{};
11231142
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1124-
auto state =
1125-
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1143+
hardware_interface::HardwareComponentParams params;
1144+
params.hardware_info = mock_hw_info;
1145+
params.clock = node->get_clock();
1146+
params.logger = node->get_logger();
1147+
auto state = system_hw.initialize(params);
11261148
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
11271149
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
11281150

@@ -1257,8 +1279,11 @@ TEST(TestComponentInterfaces, dummy_system_default)
12571279
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
12581280
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
12591281
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1260-
auto state =
1261-
system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface());
1282+
hardware_interface::HardwareComponentParams params;
1283+
params.hardware_info = dummy_system;
1284+
params.clock = node->get_clock();
1285+
params.logger = node->get_logger();
1286+
auto state = system_hw.initialize(params);
12621287
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
12631288
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
12641289

@@ -1464,8 +1489,11 @@ TEST(TestComponentInterfaces, dummy_command_mode_system)
14641489
std::make_unique<test_components::DummySystemPreparePerform>());
14651490
hardware_interface::HardwareInfo mock_hw_info{};
14661491
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1467-
auto state =
1468-
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1492+
hardware_interface::HardwareComponentParams params;
1493+
params.hardware_info = mock_hw_info;
1494+
params.clock = node->get_clock();
1495+
params.logger = node->get_logger();
1496+
auto state = system_hw.initialize(params);
14691497
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
14701498
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
14711499

@@ -1498,8 +1526,11 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior)
14981526

14991527
hardware_interface::HardwareInfo mock_hw_info{};
15001528
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
1501-
auto state =
1502-
actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1529+
hardware_interface::HardwareComponentParams params;
1530+
params.hardware_info = mock_hw_info;
1531+
params.clock = node->get_clock();
1532+
params.logger = node->get_logger();
1533+
auto state = actuator_hw.initialize(params);
15031534
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
15041535
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
15051536

@@ -1567,8 +1598,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
15671598
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
15681599
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
15691600
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1570-
auto state =
1571-
actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface());
1601+
hardware_interface::HardwareComponentParams params;
1602+
params.hardware_info = dummy_actuator;
1603+
params.clock = node->get_clock();
1604+
params.logger = node->get_logger();
1605+
auto state = actuator_hw.initialize(params);
15721606

15731607
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
15741608
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1633,8 +1667,11 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior)
16331667

16341668
hardware_interface::HardwareInfo mock_hw_info{};
16351669
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
1636-
auto state =
1637-
actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1670+
hardware_interface::HardwareComponentParams params;
1671+
params.hardware_info = mock_hw_info;
1672+
params.clock = node->get_clock();
1673+
params.logger = node->get_logger();
1674+
auto state = actuator_hw.initialize(params);
16381675
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
16391676
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
16401677

@@ -1702,8 +1739,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
17021739
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
17031740
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
17041741
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1705-
auto state =
1706-
actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface());
1742+
hardware_interface::HardwareComponentParams params;
1743+
params.hardware_info = dummy_actuator;
1744+
params.clock = node->get_clock();
1745+
params.logger = node->get_logger();
1746+
auto state = actuator_hw.initialize(params);
17071747
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
17081748
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
17091749

@@ -1767,8 +1807,11 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior)
17671807

17681808
hardware_interface::HardwareInfo mock_hw_info{};
17691809
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_components");
1770-
auto state =
1771-
sensor_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1810+
hardware_interface::HardwareComponentParams params;
1811+
params.hardware_info = mock_hw_info;
1812+
params.clock = node->get_clock();
1813+
params.logger = node->get_logger();
1814+
auto state = sensor_hw.initialize(params);
17721815

17731816
auto state_interfaces = sensor_hw.export_state_interfaces();
17741817
// Updated because is is INACTIVE
@@ -1840,8 +1883,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
18401883
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
18411884
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
18421885
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1843-
auto state =
1844-
sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface());
1886+
hardware_interface::HardwareComponentParams params;
1887+
params.hardware_info = voltage_sensor_res;
1888+
params.clock = node->get_clock();
1889+
params.logger = node->get_logger();
1890+
auto state = sensor_hw.initialize(params);
18451891

18461892
auto state_interfaces = sensor_hw.export_state_interfaces();
18471893
// Updated because is is INACTIVE
@@ -1896,8 +1942,11 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior)
18961942

18971943
hardware_interface::HardwareInfo mock_hw_info{};
18981944
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1899-
auto state =
1900-
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
1945+
hardware_interface::HardwareComponentParams params;
1946+
params.hardware_info = mock_hw_info;
1947+
params.clock = node->get_clock();
1948+
params.logger = node->get_logger();
1949+
auto state = system_hw.initialize(params);
19011950
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
19021951
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
19031952

@@ -1969,8 +2018,11 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
19692018
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
19702019
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
19712020
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
1972-
auto state =
1973-
system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface());
2021+
hardware_interface::HardwareComponentParams params;
2022+
params.hardware_info = dummy_system;
2023+
params.clock = node->get_clock();
2024+
params.logger = node->get_logger();
2025+
auto state = system_hw.initialize(params);
19742026
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
19752027
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
19762028

@@ -2036,8 +2088,11 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
20362088

20372089
hardware_interface::HardwareInfo mock_hw_info{};
20382090
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
2039-
auto state =
2040-
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
2091+
hardware_interface::HardwareComponentParams params;
2092+
params.hardware_info = mock_hw_info;
2093+
params.clock = node->get_clock();
2094+
params.logger = node->get_logger();
2095+
auto state = system_hw.initialize(params);
20412096
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
20422097
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
20432098

@@ -2109,8 +2164,11 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
21092164
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
21102165
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
21112166
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
2112-
auto state =
2113-
system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface());
2167+
hardware_interface::HardwareComponentParams params;
2168+
params.hardware_info = dummy_system;
2169+
params.clock = node->get_clock();
2170+
params.logger = node->get_logger();
2171+
auto state = system_hw.initialize(params);
21142172
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
21152173
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
21162174

hardware_interface/test/test_component_interfaces_custom_export.cpp

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -164,8 +164,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export)
164164
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
165165
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
166166
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_component");
167-
auto state =
168-
actuator_hw.initialize(dummy_actuator, node->get_logger(), node->get_node_clock_interface());
167+
hardware_interface::HardwareComponentParams params;
168+
params.hardware_info = dummy_actuator;
169+
params.clock = node->get_clock();
170+
params.logger = node->get_logger();
171+
auto state = actuator_hw.initialize(params);
169172

170173
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
171174
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -230,8 +233,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export)
230233
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
231234
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
232235
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_component");
233-
auto state =
234-
sensor_hw.initialize(voltage_sensor_res, node->get_logger(), node->get_node_clock_interface());
236+
hardware_interface::HardwareComponentParams params;
237+
params.hardware_info = voltage_sensor_res;
238+
params.clock = node->get_clock();
239+
params.logger = node->get_logger();
240+
auto state = sensor_hw.initialize(params);
235241
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
236242
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
237243

@@ -267,8 +273,11 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export)
267273
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
268274
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
269275
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_component");
270-
auto state =
271-
system_hw.initialize(dummy_system, node->get_logger(), node->get_node_clock_interface());
276+
hardware_interface::HardwareComponentParams params;
277+
params.hardware_info = dummy_system;
278+
params.clock = node->get_clock();
279+
params.logger = node->get_logger();
280+
auto state = system_hw.initialize(params);
272281
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
273282
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
274283

0 commit comments

Comments
 (0)