@@ -56,7 +56,8 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
56
56
// BEGIN (Handle export change): for backward compatibility
57
57
class DummyActuator : public hardware_interface ::ActuatorInterface
58
58
{
59
- CallbackReturn on_init (const hardware_interface::HardwareInfo & /* info*/ ) override
59
+ CallbackReturn on_init (
60
+ const hardware_interface::HardwareComponentInterfaceParams & /* info*/ ) override
60
61
{
61
62
// We hardcode the info
62
63
return CallbackReturn::SUCCESS;
@@ -169,7 +170,7 @@ class DummyActuator : public hardware_interface::ActuatorInterface
169
170
170
171
class DummyActuatorDefault : public hardware_interface ::ActuatorInterface
171
172
{
172
- CallbackReturn on_init (const hardware_interface::HardwareInfo & info) override
173
+ CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams & info) override
173
174
{
174
175
// We hardcode the info
175
176
if (
@@ -260,7 +261,8 @@ class DummyActuatorDefault : public hardware_interface::ActuatorInterface
260
261
// BEGIN (Handle export change): for backward compatibility
261
262
class DummySensor : public hardware_interface ::SensorInterface
262
263
{
263
- CallbackReturn on_init (const hardware_interface::HardwareInfo & /* info*/ ) override
264
+ CallbackReturn on_init (
265
+ const hardware_interface::HardwareComponentInterfaceParams & /* info*/ ) override
264
266
{
265
267
// We hardcode the info
266
268
return CallbackReturn::SUCCESS;
@@ -325,7 +327,7 @@ class DummySensor : public hardware_interface::SensorInterface
325
327
326
328
class DummySensorDefault : public hardware_interface ::SensorInterface
327
329
{
328
- CallbackReturn on_init (const hardware_interface::HardwareInfo & info) override
330
+ CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams & info) override
329
331
{
330
332
if (
331
333
hardware_interface::SensorInterface::on_init (info) !=
@@ -386,7 +388,7 @@ class DummySensorDefault : public hardware_interface::SensorInterface
386
388
387
389
class DummySensorJointDefault : public hardware_interface ::SensorInterface
388
390
{
389
- CallbackReturn on_init (const hardware_interface::HardwareInfo & info) override
391
+ CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams & info) override
390
392
{
391
393
if (
392
394
hardware_interface::SensorInterface::on_init (info) !=
@@ -447,7 +449,8 @@ class DummySensorJointDefault : public hardware_interface::SensorInterface
447
449
// BEGIN (Handle export change): for backward compatibility
448
450
class DummySystem : public hardware_interface ::SystemInterface
449
451
{
450
- CallbackReturn on_init (const hardware_interface::HardwareInfo & /* info */ ) override
452
+ CallbackReturn on_init (
453
+ const hardware_interface::HardwareComponentInterfaceParams & /* info */ ) override
451
454
{
452
455
// We hardcode the info
453
456
return CallbackReturn::SUCCESS;
@@ -593,7 +596,7 @@ class DummySystem : public hardware_interface::SystemInterface
593
596
594
597
class DummySystemDefault : public hardware_interface ::SystemInterface
595
598
{
596
- CallbackReturn on_init (const hardware_interface::HardwareInfo & info) override
599
+ CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams & info) override
597
600
{
598
601
if (
599
602
hardware_interface::SystemInterface::on_init (info) !=
@@ -702,7 +705,8 @@ class DummySystemDefault : public hardware_interface::SystemInterface
702
705
class DummySystemPreparePerform : public hardware_interface ::SystemInterface
703
706
{
704
707
// 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
706
710
{
707
711
// We hardcode the info
708
712
return CallbackReturn::SUCCESS;
@@ -763,8 +767,11 @@ TEST(TestComponentInterfaces, dummy_actuator)
763
767
764
768
hardware_interface::HardwareInfo mock_hw_info{};
765
769
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);
768
775
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
769
776
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
770
777
@@ -865,8 +872,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
865
872
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
866
873
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0 ];
867
874
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);
870
880
871
881
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
872
882
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
@@ -987,8 +997,11 @@ TEST(TestComponentInterfaces, dummy_sensor)
987
997
988
998
hardware_interface::HardwareInfo mock_hw_info{};
989
999
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);
992
1005
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
993
1006
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
994
1007
@@ -1027,8 +1040,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default)
1027
1040
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1028
1041
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0 ];
1029
1042
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);
1032
1048
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1033
1049
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1034
1050
@@ -1072,8 +1088,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint)
1072
1088
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1073
1089
const hardware_interface::HardwareInfo sensor_res = control_resources[0 ];
1074
1090
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);
1077
1096
ASSERT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1078
1097
ASSERT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1079
1098
@@ -1121,8 +1140,11 @@ TEST(TestComponentInterfaces, dummy_system)
1121
1140
1122
1141
hardware_interface::HardwareInfo mock_hw_info{};
1123
1142
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);
1126
1148
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1127
1149
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1128
1150
@@ -1257,8 +1279,11 @@ TEST(TestComponentInterfaces, dummy_system_default)
1257
1279
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1258
1280
const hardware_interface::HardwareInfo dummy_system = control_resources[0 ];
1259
1281
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);
1262
1287
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1263
1288
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1264
1289
@@ -1464,8 +1489,11 @@ TEST(TestComponentInterfaces, dummy_command_mode_system)
1464
1489
std::make_unique<test_components::DummySystemPreparePerform>());
1465
1490
hardware_interface::HardwareInfo mock_hw_info{};
1466
1491
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);
1469
1497
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1470
1498
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1471
1499
@@ -1498,8 +1526,11 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior)
1498
1526
1499
1527
hardware_interface::HardwareInfo mock_hw_info{};
1500
1528
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);
1503
1534
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1504
1535
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1505
1536
@@ -1567,8 +1598,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
1567
1598
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1568
1599
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0 ];
1569
1600
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);
1572
1606
1573
1607
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1574
1608
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
@@ -1633,8 +1667,11 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior)
1633
1667
1634
1668
hardware_interface::HardwareInfo mock_hw_info{};
1635
1669
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);
1638
1675
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1639
1676
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1640
1677
@@ -1702,8 +1739,11 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
1702
1739
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1703
1740
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0 ];
1704
1741
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);
1707
1747
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1708
1748
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1709
1749
@@ -1767,8 +1807,11 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior)
1767
1807
1768
1808
hardware_interface::HardwareInfo mock_hw_info{};
1769
1809
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);
1772
1815
1773
1816
auto state_interfaces = sensor_hw.export_state_interfaces ();
1774
1817
// Updated because is is INACTIVE
@@ -1840,8 +1883,11 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
1840
1883
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1841
1884
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0 ];
1842
1885
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);
1845
1891
1846
1892
auto state_interfaces = sensor_hw.export_state_interfaces ();
1847
1893
// Updated because is is INACTIVE
@@ -1896,8 +1942,11 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior)
1896
1942
1897
1943
hardware_interface::HardwareInfo mock_hw_info{};
1898
1944
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);
1901
1950
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1902
1951
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1903
1952
@@ -1969,8 +2018,11 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
1969
2018
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
1970
2019
const hardware_interface::HardwareInfo dummy_system = control_resources[0 ];
1971
2020
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);
1974
2026
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
1975
2027
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
1976
2028
@@ -2036,8 +2088,11 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
2036
2088
2037
2089
hardware_interface::HardwareInfo mock_hw_info{};
2038
2090
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);
2041
2096
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
2042
2097
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
2043
2098
@@ -2109,8 +2164,11 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
2109
2164
hardware_interface::parse_control_resources_from_urdf (urdf_to_test);
2110
2165
const hardware_interface::HardwareInfo dummy_system = control_resources[0 ];
2111
2166
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);
2114
2172
EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
2115
2173
EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
2116
2174
0 commit comments