Skip to content

Commit 1bbb033

Browse files
authored
Add in a fix for older compilers. (#2075)
* Add in a fix for older compilers. The addition of the NodeInterfaces class made it stop compiling with older compilers (such as gcc 9.4.0 on Ubuntu 20.04). The error has to do with calling the copy constructor on rclcpp::Node, which is deleted. Work around this by removing the NodeInterfaces shared_ptr constructor, which isn't technically needed. Signed-off-by: Chris Lalancette <[email protected]>
1 parent c63f9ea commit 1bbb033

File tree

2 files changed

+6
-12
lines changed

2 files changed

+6
-12
lines changed

rclcpp/include/rclcpp/node_interfaces/node_interfaces.hpp

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

150-
/// NodeT::SharedPtr Constructor
151-
template<typename NodeT>
152-
NodeInterfaces(std::shared_ptr<NodeT> node) // NOLINT(runtime/explicit)
153-
: NodeInterfaces(node ? *node : throw std::invalid_argument("given node pointer is nullptr"))
154-
{}
155-
156150
explicit NodeInterfaces(std::shared_ptr<InterfaceTs>... args)
157151
: NodeInterfacesSupportsT(args ...)
158152
{}

rclcpp/test/rclcpp/node_interfaces/test_node_interfaces.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ TEST_F(TestNodeInterfaces, node_interfaces_nominal) {
4444
using rclcpp::node_interfaces::NodeInterfaces;
4545
using rclcpp::node_interfaces::NodeBaseInterface;
4646
using rclcpp::node_interfaces::NodeGraphInterface;
47-
auto node_interfaces = NodeInterfaces<NodeBaseInterface, NodeGraphInterface>(node);
47+
auto node_interfaces = NodeInterfaces<NodeBaseInterface, NodeGraphInterface>(*node);
4848
}
4949

5050
// Implicit conversion of rclcpp::Node into function that uses NodeInterfaces of base.
@@ -55,7 +55,7 @@ TEST_F(TestNodeInterfaces, node_interfaces_nominal) {
5555
auto base_interface = ni.get<NodeBaseInterface>();
5656
};
5757

58-
some_func(node);
58+
some_func(*node);
5959
}
6060

6161
// Implicit narrowing of NodeInterfaces into a new interface NodeInterfaces with fewer interfaces.
@@ -67,7 +67,7 @@ TEST_F(TestNodeInterfaces, node_interfaces_nominal) {
6767
auto base_interface = ni_with_one.get<NodeBaseInterface>();
6868
};
6969

70-
NodeInterfaces<NodeBaseInterface, NodeGraphInterface> ni_with_two(node);
70+
NodeInterfaces<NodeBaseInterface, NodeGraphInterface> ni_with_two(*node);
7171

7272
some_func(ni_with_two);
7373
}
@@ -102,7 +102,7 @@ TEST_F(TestNodeInterfaces, node_interfaces_standard_interfaces) {
102102
rclcpp::node_interfaces::NodeWaitablesInterface,
103103
rclcpp::node_interfaces::NodeParametersInterface,
104104
rclcpp::node_interfaces::NodeTimeSourceInterface
105-
>(node);
105+
>(*node);
106106
}
107107

108108
/*
@@ -134,7 +134,7 @@ TEST_F(TestNodeInterfaces, ni_init) {
134134
NodeWaitablesInterface,
135135
NodeParametersInterface,
136136
NodeTimeSourceInterface
137-
>(node);
137+
>(*node);
138138

139139
{
140140
auto base = ni.get<NodeBaseInterface>();
@@ -198,7 +198,7 @@ TEST_F(TestNodeInterfaces, ni_all_init) {
198198
using rclcpp::node_interfaces::NodeParametersInterface;
199199
using rclcpp::node_interfaces::NodeTimeSourceInterface;
200200

201-
auto ni = rclcpp::node_interfaces::NodeInterfaces<ALL_RCLCPP_NODE_INTERFACES>(node);
201+
auto ni = rclcpp::node_interfaces::NodeInterfaces<ALL_RCLCPP_NODE_INTERFACES>(*node);
202202

203203
{
204204
auto base = ni.get<NodeBaseInterface>();

0 commit comments

Comments
 (0)