Skip to content

Commit 1cabf60

Browse files
committed
fixed tests for component interfaces
1 parent c993e5b commit 1cabf60

File tree

2 files changed

+63
-9
lines changed

2 files changed

+63
-9
lines changed

hardware_interface/test/test_component_interfaces.cpp

Lines changed: 56 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3333
#include "hardware_interface/types/lifecycle_state_names.hpp"
3434
#include "lifecycle_msgs/msg/state.hpp"
35+
#include "rclcpp/executors/single_threaded_executor.hpp"
3536
#include "rclcpp/node.hpp"
3637
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3738
#include "ros2_control_test_assets/components_urdfs.hpp"
@@ -769,12 +770,15 @@ TEST(TestComponentInterfaces, dummy_actuator)
769770
{
770771
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());
771772

772-
hardware_interface::HardwareInfo mock_hw_info{};
773+
hardware_interface::HardwareInfo mock_hw_info;
774+
mock_hw_info.name = "mock_hw";
773775
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
774776
hardware_interface::HardwareComponentParams params;
775777
params.hardware_info = mock_hw_info;
776778
params.clock = node->get_clock();
777779
params.logger = node->get_logger();
780+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
781+
params.executor = executor;
778782
auto state = actuator_hw.initialize(params);
779783
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
780784
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -880,6 +884,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
880884
params.hardware_info = dummy_actuator;
881885
params.clock = node->get_clock();
882886
params.logger = node->get_logger();
887+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
888+
params.executor = executor;
883889
auto state = actuator_hw.initialize(params);
884890

885891
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
@@ -997,12 +1003,15 @@ TEST(TestComponentInterfaces, dummy_sensor)
9971003
{
9981004
hardware_interface::Sensor sensor_hw(std::make_unique<test_components::DummySensor>());
9991005

1000-
hardware_interface::HardwareInfo mock_hw_info{};
1006+
hardware_interface::HardwareInfo mock_hw_info;
1007+
mock_hw_info.name = "mock_hw";
10011008
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_components");
10021009
hardware_interface::HardwareComponentParams params;
10031010
params.hardware_info = mock_hw_info;
10041011
params.clock = node->get_clock();
10051012
params.logger = node->get_logger();
1013+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1014+
params.executor = executor;
10061015
auto state = sensor_hw.initialize(params);
10071016
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
10081017
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1046,6 +1055,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default)
10461055
params.hardware_info = voltage_sensor_res;
10471056
params.clock = node->get_clock();
10481057
params.logger = node->get_logger();
1058+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1059+
params.executor = executor;
10491060
auto state = sensor_hw.initialize(params);
10501061
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
10511062
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1094,6 +1105,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default_joint)
10941105
params.hardware_info = sensor_res;
10951106
params.clock = node->get_clock();
10961107
params.logger = node->get_logger();
1108+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1109+
params.executor = executor;
10971110
auto state = sensor_hw.initialize(params);
10981111
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
10991112
ASSERT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1140,12 +1153,15 @@ TEST(TestComponentInterfaces, dummy_system)
11401153
{
11411154
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());
11421155

1143-
hardware_interface::HardwareInfo mock_hw_info{};
1156+
hardware_interface::HardwareInfo mock_hw_info;
1157+
mock_hw_info.name = "mock_hw";
11441158
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
11451159
hardware_interface::HardwareComponentParams params;
11461160
params.hardware_info = mock_hw_info;
11471161
params.clock = node->get_clock();
11481162
params.logger = node->get_logger();
1163+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1164+
params.executor = executor;
11491165
auto state = system_hw.initialize(params);
11501166
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
11511167
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1285,6 +1301,8 @@ TEST(TestComponentInterfaces, dummy_system_default)
12851301
params.hardware_info = dummy_system;
12861302
params.clock = node->get_clock();
12871303
params.logger = node->get_logger();
1304+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1305+
params.executor = executor;
12881306
auto state = system_hw.initialize(params);
12891307
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
12901308
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1489,12 +1507,16 @@ TEST(TestComponentInterfaces, dummy_command_mode_system)
14891507
{
14901508
hardware_interface::System system_hw(
14911509
std::make_unique<test_components::DummySystemPreparePerform>());
1492-
hardware_interface::HardwareInfo mock_hw_info{};
1510+
1511+
hardware_interface::HardwareInfo mock_hw_info;
1512+
mock_hw_info.name = "mock_hw";
14931513
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
14941514
hardware_interface::HardwareComponentParams params;
14951515
params.hardware_info = mock_hw_info;
14961516
params.clock = node->get_clock();
14971517
params.logger = node->get_logger();
1518+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1519+
params.executor = executor;
14981520
auto state = system_hw.initialize(params);
14991521
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
15001522
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1526,12 +1548,15 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior)
15261548
{
15271549
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());
15281550

1529-
hardware_interface::HardwareInfo mock_hw_info{};
1551+
hardware_interface::HardwareInfo mock_hw_info;
1552+
mock_hw_info.name = "mock_hw";
15301553
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
15311554
hardware_interface::HardwareComponentParams params;
15321555
params.hardware_info = mock_hw_info;
15331556
params.clock = node->get_clock();
15341557
params.logger = node->get_logger();
1558+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1559+
params.executor = executor;
15351560
auto state = actuator_hw.initialize(params);
15361561
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
15371562
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1604,6 +1629,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
16041629
params.hardware_info = dummy_actuator;
16051630
params.clock = node->get_clock();
16061631
params.logger = node->get_logger();
1632+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1633+
params.executor = executor;
16071634
auto state = actuator_hw.initialize(params);
16081635

16091636
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
@@ -1667,12 +1694,15 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior)
16671694
{
16681695
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());
16691696

1670-
hardware_interface::HardwareInfo mock_hw_info{};
1697+
hardware_interface::HardwareInfo mock_hw_info;
1698+
mock_hw_info.name = "mock_hw";
16711699
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
16721700
hardware_interface::HardwareComponentParams params;
16731701
params.hardware_info = mock_hw_info;
16741702
params.clock = node->get_clock();
16751703
params.logger = node->get_logger();
1704+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1705+
params.executor = executor;
16761706
auto state = actuator_hw.initialize(params);
16771707
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
16781708
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1745,6 +1775,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
17451775
params.hardware_info = dummy_actuator;
17461776
params.clock = node->get_clock();
17471777
params.logger = node->get_logger();
1778+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1779+
params.executor = executor;
17481780
auto state = actuator_hw.initialize(params);
17491781
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
17501782
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -1807,12 +1839,15 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior)
18071839
{
18081840
hardware_interface::Sensor sensor_hw(std::make_unique<test_components::DummySensor>());
18091841

1810-
hardware_interface::HardwareInfo mock_hw_info{};
1842+
hardware_interface::HardwareInfo mock_hw_info;
1843+
mock_hw_info.name = "mock_hw";
18111844
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_components");
18121845
hardware_interface::HardwareComponentParams params;
18131846
params.hardware_info = mock_hw_info;
18141847
params.clock = node->get_clock();
18151848
params.logger = node->get_logger();
1849+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1850+
params.executor = executor;
18161851
auto state = sensor_hw.initialize(params);
18171852

18181853
auto state_interfaces = sensor_hw.export_state_interfaces();
@@ -1889,6 +1924,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
18891924
params.hardware_info = voltage_sensor_res;
18901925
params.clock = node->get_clock();
18911926
params.logger = node->get_logger();
1927+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1928+
params.executor = executor;
18921929
auto state = sensor_hw.initialize(params);
18931930

18941931
auto state_interfaces = sensor_hw.export_state_interfaces();
@@ -1942,12 +1979,15 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior)
19421979
{
19431980
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());
19441981

1945-
hardware_interface::HardwareInfo mock_hw_info{};
1982+
hardware_interface::HardwareInfo mock_hw_info;
1983+
mock_hw_info.name = "mock_hw";
19461984
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
19471985
hardware_interface::HardwareComponentParams params;
19481986
params.hardware_info = mock_hw_info;
19491987
params.clock = node->get_clock();
19501988
params.logger = node->get_logger();
1989+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
1990+
params.executor = executor;
19511991
auto state = system_hw.initialize(params);
19521992
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
19531993
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -2024,6 +2064,8 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
20242064
params.hardware_info = dummy_system;
20252065
params.clock = node->get_clock();
20262066
params.logger = node->get_logger();
2067+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
2068+
params.executor = executor;
20272069
auto state = system_hw.initialize(params);
20282070
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
20292071
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -2088,12 +2130,15 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
20882130
{
20892131
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());
20902132

2091-
hardware_interface::HardwareInfo mock_hw_info{};
2133+
hardware_interface::HardwareInfo mock_hw_info;
2134+
mock_hw_info.name = "mock_hw";
20922135
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
20932136
hardware_interface::HardwareComponentParams params;
20942137
params.hardware_info = mock_hw_info;
20952138
params.clock = node->get_clock();
20962139
params.logger = node->get_logger();
2140+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
2141+
params.executor = executor;
20972142
auto state = system_hw.initialize(params);
20982143
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
20992144
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -2170,6 +2215,8 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
21702215
params.hardware_info = dummy_system;
21712216
params.clock = node->get_clock();
21722217
params.logger = node->get_logger();
2218+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
2219+
params.executor = executor;
21732220
auto state = system_hw.initialize(params);
21742221
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
21752222
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

hardware_interface/test/test_component_interfaces_custom_export.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3333
#include "hardware_interface/types/lifecycle_state_names.hpp"
3434
#include "lifecycle_msgs/msg/state.hpp"
35+
#include "rclcpp/executors/single_threaded_executor.hpp"
3536
#include "rclcpp/node.hpp"
3637
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3738
#include "ros2_control_test_assets/components_urdfs.hpp"
@@ -167,6 +168,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export)
167168
params.hardware_info = dummy_actuator;
168169
params.clock = node->get_clock();
169170
params.logger = node->get_logger();
171+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
172+
params.executor = executor;
170173
auto state = actuator_hw.initialize(params);
171174

172175
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
@@ -236,6 +239,8 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export)
236239
params.hardware_info = voltage_sensor_res;
237240
params.clock = node->get_clock();
238241
params.logger = node->get_logger();
242+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
243+
params.executor = executor;
239244
auto state = sensor_hw.initialize(params);
240245
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
241246
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
@@ -276,6 +281,8 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export)
276281
params.hardware_info = dummy_system;
277282
params.clock = node->get_clock();
278283
params.logger = node->get_logger();
284+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
285+
params.executor = executor;
279286
auto state = system_hw.initialize(params);
280287
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
281288
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

0 commit comments

Comments
 (0)