Skip to content

Commit 97c5c11

Browse files
authored
Add default constructor to NodeInterfaces (#2094)
* Add default constructor to NodeInterfaces Signed-off-by: Shane Loretz <[email protected]> * Remove unnecessary NOLINT Signed-off-by: Shane Loretz <[email protected]> --------- Signed-off-by: Shane Loretz <[email protected]> Signed-off-by: Shane Loretz <[email protected]>
1 parent 7d660ac commit 97c5c11

File tree

3 files changed

+18
-0
lines changed

3 files changed

+18
-0
lines changed

rclcpp/include/rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,10 @@ struct NodeInterfacesStorage
4444
: interfaces_(init_tuple<decltype(node), InterfaceTs ...>(node))
4545
{}
4646

47+
NodeInterfacesStorage()
48+
: interfaces_()
49+
{}
50+
4751
explicit NodeInterfacesStorage(std::shared_ptr<InterfaceTs>... args)
4852
: interfaces_(args ...)
4953
{}

rclcpp/include/rclcpp/node_interfaces/node_interfaces.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,11 @@ class NodeInterfaces
147147
: NodeInterfacesSupportsT(node)
148148
{}
149149

150+
// Create a NodeInterfaces object with no bound interfaces
151+
NodeInterfaces()
152+
: NodeInterfacesSupportsT()
153+
{}
154+
150155
explicit NodeInterfaces(std::shared_ptr<InterfaceTs>... args)
151156
: NodeInterfacesSupportsT(args ...)
152157
{}

rclcpp/test/rclcpp/node_interfaces/test_node_interfaces.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,15 @@ class TestNodeInterfaces : public ::testing::Test
3333
}
3434
};
3535

36+
TEST_F(TestNodeInterfaces, default_constructor) {
37+
auto node = std::make_shared<rclcpp::Node>("my_node");
38+
using rclcpp::node_interfaces::NodeInterfaces;
39+
using rclcpp::node_interfaces::NodeBaseInterface;
40+
using rclcpp::node_interfaces::NodeGraphInterface;
41+
NodeInterfaces<NodeBaseInterface, NodeGraphInterface> interfaces;
42+
interfaces = NodeInterfaces<NodeBaseInterface, NodeGraphInterface>(*node);
43+
}
44+
3645
/*
3746
Testing NodeInterfaces construction from nodes.
3847
*/

0 commit comments

Comments
 (0)