Skip to content

Commit 2d70891

Browse files
soham2560saikishor
andauthored
Update hardware_interface_testing/test/test_resource_manager.cpp
Co-authored-by: Sai Kishor Kothakota <saisastra3@gmail.com>
1 parent c1c726d commit 2d70891

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

hardware_interface_testing/test/test_resource_manager.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1349,13 +1349,15 @@ class MockExecutor : public rclcpp::executors::SingleThreadedExecutor
13491349
: rclcpp::executors::SingleThreadedExecutor(options)
13501350
{
13511351
}
1352-
std::vector<std::string> added_node_names;
1352+
13531353
void add_node(
13541354
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify) override
13551355
{
13561356
rclcpp::executors::SingleThreadedExecutor::add_node(node_ptr, notify);
13571357
added_node_names.push_back(node_ptr->get_name());
13581358
}
1359+
1360+
std::vector<std::string> added_node_names;
13591361
};
13601362

13611363
TEST_F(ResourceManagerTest, hardware_nodes_are_added_to_mock_executor_on_load)

0 commit comments

Comments
 (0)