Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1559,6 +1559,10 @@ class Node : public std::enable_shared_from_this<Node>
* which has been created using an existing instance of this class, but which
* has an additional sub-namespace (short for subordinate namespace)
* associated with it.
* A subordinate node and an instance of this class share all the node interfaces
* such as `rclcpp::node_interfaces::NodeParameterInterface`.
* Subordinate nodes are primarily used to organize namespaces and provide a
* hierarchical structure, but they are not meant to be completely independent nodes.
* The sub-namespace will extend the node's namespace for the purpose of
* creating additional entities, such as Publishers, Subscriptions, Service
* Clients and Servers, and so on.
Expand Down
8 changes: 2 additions & 6 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,11 +323,9 @@ template<typename ParameterT>
bool
Node::get_parameter(const std::string & name, ParameterT & parameter) const
{
std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());

rclcpp::Parameter parameter_variant;

bool result = get_parameter(sub_name, parameter_variant);
bool result = get_parameter(name, parameter_variant);
if (result) {
parameter = static_cast<ParameterT>(parameter_variant.get_value<ParameterT>());
}
Expand All @@ -342,9 +340,7 @@ Node::get_parameter_or(
ParameterT & parameter,
const ParameterT & alternative_value) const
{
std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());

bool got_parameter = get_parameter(sub_name, parameter);
bool got_parameter = get_parameter(name, parameter);
if (!got_parameter) {
parameter = alternative_value;
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -689,7 +689,7 @@ Node::create_generic_client(
node_base_,
node_graph_,
node_services_,
service_name,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
service_type,
qos,
group);
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_generic_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ TEST_F(TestGenericClient, wait_for_service) {
TEST_F(TestGenericClientSub, construction_and_destruction) {
{
auto client = subnode->create_generic_client("test_service", "test_msgs/srv/Empty");
EXPECT_STREQ(client->get_service_name(), "/ns/test_service");
EXPECT_STREQ(client->get_service_name(), "/ns/sub_ns/test_service");
}

{
Expand Down
33 changes: 33 additions & 0 deletions rclcpp/test/rclcpp/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,6 +306,39 @@ TEST_F(TestNode, subnode_get_name_and_namespace) {
}, rclcpp::exceptions::NameValidationError);
}
}

TEST_F(TestNode, subnode_parameter_operation) {
auto node = std::make_shared<rclcpp::Node>("my_node", "ns");
auto subnode = node->create_sub_node("sub_ns");

auto value = subnode->declare_parameter("param", 5);
EXPECT_EQ(value, 5);
// node and sub-node shares NodeParameterInterface, so expecting the exception.
EXPECT_THROW(
node->declare_parameter("param", 0),
rclcpp::exceptions::ParameterAlreadyDeclaredException);
rclcpp::Parameter param;

node->get_parameter("param", param);
EXPECT_EQ(param.get_value<int>(), 5);
subnode->get_parameter("param", param);
EXPECT_EQ(param.get_value<int>(), 5);

int param_int;
node->get_parameter("param", param_int);
EXPECT_EQ(param_int, 5);
subnode->get_parameter("param", param_int);
EXPECT_EQ(param_int, 5);

EXPECT_EQ(node->get_parameter_or("param", 333), 5);
EXPECT_EQ(subnode->get_parameter_or("param", 666), 5);

node->get_parameter_or("param", param_int, 333);
EXPECT_EQ(param_int, 5);
subnode->get_parameter_or("param", param_int, 666);
EXPECT_EQ(param_int, 5);
}

/*
Testing node construction and destruction.
*/
Expand Down