From 5a74f32ba0a09e5a2423f6b9b6729cfb3a2d050c Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 15 May 2015 14:01:27 -0700 Subject: [PATCH 1/9] Added developer parameter API --- rclcpp/include/rclcpp/parameter.hpp | 8 ++ rclcpp/include/rclcpp/parameter_client.hpp | 122 +++++++++++++++++++-- 2 files changed, 120 insertions(+), 10 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 26bba4f..30cde6f 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -190,6 +190,14 @@ public: } } + rcl_interfaces::Parameter to_parameter() + { + rcl_interfaces::Parameter parameter; + parameter.name = name_; + parameter.value = value_; + return parameter; + } + private: std::string name_; rcl_interfaces::ParameterValue value_; diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 1e17533..e8016e8 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -67,8 +67,35 @@ public: std::function>)> callback = nullptr) { - std::shared_future> f; - return f; + std::promise> promise_result; + auto future_result = promise_result.get_future().share(); + + auto request = std::make_shared(); + request->names = names; + + get_parameters_client_->async_send_request( + request, + [&names, &promise_result, &future_result, &callback]( + rclcpp::client::Client::SharedFuture cb_f) { + std::vector parameter_variants; + auto & pvalues = cb_f.get()->values; + + std::transform(pvalues.begin(), pvalues.end(), std::back_inserter(parameter_variants), + [&names, &pvalues](rcl_interfaces::ParameterValue pvalue) { + auto i = &pvalue - &pvalues[0]; + rcl_interfaces::Parameter parameter; + parameter.name = names[i]; + parameter.value = pvalue; + return rclcpp::parameter::ParameterVariant::from_parameter(parameter); + }); + promise_result.set_value(parameter_variants); + if (callback != nullptr) { + callback(future_result); + } + } + ); + + return future_result; } std::shared_future> @@ -77,8 +104,28 @@ public: std::function>)> callback = nullptr) { - std::shared_future> f; - return f; + std::promise> promise_result; + auto future_result = promise_result.get_future().share(); + + auto request = std::make_shared(); + request->parameter_names = parameter_names; + + get_parameter_types_client_->async_send_request( + request, + [&promise_result, &future_result, &callback]( + rclcpp::client::Client::SharedFuture cb_f) { + std::vector parameter_types; + auto & pts = cb_f.get()->parameter_types; + std::transform(pts.begin(), pts.end(), std::back_inserter(parameter_types), + [](uint8_t pt) {return static_cast(pt); }); + promise_result.set_value(parameter_types); + if (callback != nullptr) { + callback(future_result); + } + } + ); + + return future_result; } std::shared_future> @@ -87,8 +134,27 @@ public: std::function>)> callback = nullptr) { - std::shared_future> f; - return f; + std::promise> promise_result; + auto future_result = promise_result.get_future().share(); + + auto request = std::make_shared(); + + std::transform(parameters.begin(), parameters.end(), std::back_inserter( + request->parameters), []( + rclcpp::parameter::ParameterVariant p) {return p.to_parameter(); }); + + set_parameters_client_->async_send_request( + request, + [&promise_result, &future_result, &callback]( + rclcpp::client::Client::SharedFuture cb_f) { + promise_result.set_value(cb_f.get()->results); + if (callback != nullptr) { + callback(future_result); + } + } + ); + + return future_result; } std::shared_future @@ -97,8 +163,27 @@ public: std::function)> callback = nullptr) { - std::shared_future f; - return f; + std::promise promise_result; + auto future_result = promise_result.get_future().share(); + + auto request = std::make_shared(); + + std::transform(parameters.begin(), parameters.end(), std::back_inserter( + request->parameters), []( + rclcpp::parameter::ParameterVariant p) {return p.to_parameter(); }); + + set_parameters_atomically_client_->async_send_request( + request, + [&promise_result, &future_result, &callback]( + rclcpp::client::Client::SharedFuture cb_f) { + promise_result.set_value(cb_f.get()->result); + if (callback != nullptr) { + callback(future_result); + } + } + ); + + return future_result; } std::shared_future @@ -108,8 +193,25 @@ public: std::function)> callback = nullptr) { - std::shared_future f; - return f; + std::promise promise_result; + auto future_result = promise_result.get_future().share(); + + auto request = std::make_shared(); + request->parameter_prefixes = parameter_prefixes; + request->depth = depth; + + list_parameters_client_->async_send_request( + request, + [&promise_result, &future_result, &callback]( + rclcpp::client::Client::SharedFuture cb_f) { + promise_result.set_value(cb_f.get()->result); + if (callback != nullptr) { + callback(future_result); + } + } + ); + + return future_result; } private: From 21d766b51167d92949cad65fbbb7fd4b77a3d285 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 16:34:46 -0700 Subject: [PATCH 2/9] Implement get_name() --- rclcpp/include/rclcpp/node.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 5b76e7a..2d34249 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -95,8 +95,8 @@ public: Node(std::string node_name, rclcpp::context::Context::SharedPtr context); /* Get the name of the node. */ - std::string - get_name(); + const std::string & + get_name() const {return name_; } /* Create and return a callback group. */ rclcpp::callback_group::CallbackGroup::SharedPtr From 5c43e835c71b368595fac5bca9382042f26b91d8 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 16:35:38 -0700 Subject: [PATCH 3/9] Use rclcpp::parameter::ParameterVariant --- rclcpp/include/rclcpp/node.hpp | 4 ++-- rclcpp/include/rclcpp/node_impl.hpp | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 2d34249..e12a866 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -149,10 +149,10 @@ public: rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); const std::vector set_parameters( - const std::vector & parameters); + const std::vector & parameters); const rcl_interfaces::SetParametersResult set_parameters_atomically( - const std::vector & parameters); + const std::vector & parameters); const std::vector get_parameters( const std::vector & names); diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 381b573..cb84d88 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -215,12 +215,12 @@ Node::create_service( const std::vector Node::set_parameters( - const std::vector & parameters) + const std::vector & parameters) { std::lock_guard lock(mutex_); std::vector results; for (auto p : parameters) { - parameters_[p.name] = rclcpp::parameter::ParameterVariant::from_parameter(p); + parameters_[p.get_name()] = p; rcl_interfaces::SetParametersResult result; result.successful = true; // TODO: handle parameter constraints @@ -231,12 +231,12 @@ Node::set_parameters( const rcl_interfaces::SetParametersResult Node::set_parameters_atomically( - const std::vector & parameters) + const std::vector & parameters) { std::lock_guard lock(mutex_); std::map tmp_map; for (auto p : parameters) { - tmp_map[p.name] = rclcpp::parameter::ParameterVariant::from_parameter(p); + tmp_map[p.get_name()] = p; } tmp_map.insert(parameters_.begin(), parameters_.end()); std::swap(tmp_map, parameters_); From 1f2ab33988f8a609df939f01f4c90f7e9da2c99e Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 16:36:17 -0700 Subject: [PATCH 4/9] Only return a single ListParametersResult --- rclcpp/include/rclcpp/node.hpp | 2 +- rclcpp/include/rclcpp/node_impl.hpp | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index e12a866..3849693 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -163,7 +163,7 @@ public: const std::vector get_parameter_types( const std::vector & names); - const std::vector list_parameters( + const rcl_interfaces::ListParametersResult list_parameters( const std::vector & prefixes, uint64_t depth); private: diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index cb84d88..3133a96 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -302,12 +302,12 @@ Node::get_parameter_types( return results; } -const std::vector +const rcl_interfaces::ListParametersResult Node::list_parameters( const std::vector & prefixes, uint64_t depth) { std::lock_guard lock(mutex_); - std::vector results; + rcl_interfaces::ListParametersResult result; // TODO: define parameter separator, use "." for now for (auto & kv : parameters_) { @@ -320,7 +320,6 @@ Node::list_parameters( return false; })) { - rcl_interfaces::ListParametersResult result; result.parameter_names.push_back(kv.first); size_t last_separator = kv.first.find_last_of('.'); std::string prefix = kv.first.substr(0, last_separator); @@ -329,9 +328,8 @@ Node::list_parameters( { result.parameter_prefixes.push_back(prefix); } - results.push_back(result); } } - return results; + return result; } #endif /* RCLCPP_RCLCPP_NODE_IMPL_HPP_ */ From 2bb3623de2fe8b495359bb344d793857808ce0a4 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 16:36:34 -0700 Subject: [PATCH 5/9] Added remote_node_name --- rclcpp/include/rclcpp/parameter_client.hpp | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index e8016e8..22521eb 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -46,19 +46,25 @@ class AsyncParametersClient public: RCLCPP_MAKE_SHARED_DEFINITIONS(AsyncParametersClient); - AsyncParametersClient(const rclcpp::node::Node::SharedPtr & node) + AsyncParametersClient(const rclcpp::node::Node::SharedPtr & node, + const std::string & remote_node_name = "") : node_(node) { + if (remote_node_name != "") { + remote_node_name_ = remote_node_name; + } else { + remote_node_name_ = node_->get_name(); + } get_parameters_client_ = node_->create_client( - "get_parameters"); + "get_parameters_" + remote_node_name_); get_parameter_types_client_ = node_->create_client( - "get_parameter_types"); + "get_parameter_types_" + remote_node_name_); set_parameters_client_ = node_->create_client( - "set_parameters"); + "set_parameters_" + remote_node_name_); list_parameters_client_ = node_->create_client( - "list_parameters"); + "list_parameters_" + remote_node_name_); describe_parameters_client_ = node_->create_client( - "describe_parameters"); + "describe_parameters_" + remote_node_name_); } std::shared_future> @@ -223,6 +229,7 @@ private: set_parameters_atomically_client_; rclcpp::client::Client::SharedPtr list_parameters_client_; rclcpp::client::Client::SharedPtr describe_parameters_client_; + std::string remote_node_name_; }; class SyncParametersClient From 4a71a6a446b383b8236af659010c3815ba42ceb0 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 16:45:32 -0700 Subject: [PATCH 6/9] Made list, describe and get methods const --- rclcpp/include/rclcpp/node.hpp | 22 +++++++++++----------- rclcpp/include/rclcpp/node_impl.hpp | 20 ++++++++++---------- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 3849693..3661176 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -148,23 +148,23 @@ public: FunctorT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); - const std::vector set_parameters( + std::vector set_parameters( const std::vector & parameters); - const rcl_interfaces::SetParametersResult set_parameters_atomically( + rcl_interfaces::SetParametersResult set_parameters_atomically( const std::vector & parameters); - const std::vector get_parameters( - const std::vector & names); + std::vector get_parameters( + const std::vector & names) const; - const std::vector describe_parameters( - const std::vector & names); + std::vector describe_parameters( + const std::vector & names) const; - const std::vector get_parameter_types( - const std::vector & names); + std::vector get_parameter_types( + const std::vector & names) const; - const rcl_interfaces::ListParametersResult list_parameters( - const std::vector & prefixes, uint64_t depth); + rcl_interfaces::ListParametersResult list_parameters( + const std::vector & prefixes, uint64_t depth) const; private: RCLCPP_DISABLE_COPY(Node); @@ -186,7 +186,7 @@ private: size_t number_of_services_; size_t number_of_clients_; - std::mutex mutex_; + mutable std::mutex mutex_; std::map parameters_; diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 3133a96..185fd89 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -213,7 +213,7 @@ Node::create_service( return serv; } -const std::vector +std::vector Node::set_parameters( const std::vector & parameters) { @@ -229,7 +229,7 @@ Node::set_parameters( return results; } -const rcl_interfaces::SetParametersResult +rcl_interfaces::SetParametersResult Node::set_parameters_atomically( const std::vector & parameters) { @@ -246,9 +246,9 @@ Node::set_parameters_atomically( return result; } -const std::vector +std::vector Node::get_parameters( - const std::vector & names) + const std::vector & names) const { std::lock_guard lock(mutex_); std::vector results; @@ -263,9 +263,9 @@ Node::get_parameters( return results; } -const std::vector +std::vector Node::describe_parameters( - const std::vector & names) + const std::vector & names) const { std::lock_guard lock(mutex_); std::vector results; @@ -283,9 +283,9 @@ Node::describe_parameters( return results; } -const std::vector +std::vector Node::get_parameter_types( - const std::vector & names) + const std::vector & names) const { std::lock_guard lock(mutex_); std::vector results; @@ -302,9 +302,9 @@ Node::get_parameter_types( return results; } -const rcl_interfaces::ListParametersResult +rcl_interfaces::ListParametersResult Node::list_parameters( - const std::vector & prefixes, uint64_t depth) + const std::vector & prefixes, uint64_t depth) const { std::lock_guard lock(mutex_); rcl_interfaces::ListParametersResult result; From aa69694e1b1447a70799082c099e8b9b67c147df Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 17:36:33 -0700 Subject: [PATCH 7/9] Prepend parameter methods with the remote node name --- rclcpp/include/rclcpp/parameter_client.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 22521eb..69aa99c 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -56,15 +56,15 @@ public: remote_node_name_ = node_->get_name(); } get_parameters_client_ = node_->create_client( - "get_parameters_" + remote_node_name_); + remote_node_name_ + "__get_parameters"); get_parameter_types_client_ = node_->create_client( - "get_parameter_types_" + remote_node_name_); + remote_node_name_ + "__get_parameter_types"); set_parameters_client_ = node_->create_client( - "set_parameters_" + remote_node_name_); + remote_node_name_ + "__set_parameters"); list_parameters_client_ = node_->create_client( - "list_parameters_" + remote_node_name_); + remote_node_name_ + "__list_parameters"); describe_parameters_client_ = node_->create_client( - "describe_parameters_" + remote_node_name_); + remote_node_name_ + "__describe_parameters"); } std::shared_future> From 81b649d76c3b6a678d80520b06df80e0bc5d06ed Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 16:36:56 -0700 Subject: [PATCH 8/9] Added external API --- rclcpp/include/rclcpp/parameter_service.hpp | 160 ++++++++++++++++++++ rclcpp/include/rclcpp/rclcpp.hpp | 1 + 2 files changed, 161 insertions(+) create mode 100644 rclcpp/include/rclcpp/parameter_service.hpp diff --git a/rclcpp/include/rclcpp/parameter_service.hpp b/rclcpp/include/rclcpp/parameter_service.hpp new file mode 100644 index 0000000..3507fa1 --- /dev/null +++ b/rclcpp/include/rclcpp/parameter_service.hpp @@ -0,0 +1,160 @@ +// Copyright 2015 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP_RCLCPP_PARAMETER_SERVICE_HPP_ +#define RCLCPP_RCLCPP_PARAMETER_SERVICE_HPP_ + +#include + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace rclcpp +{ + +namespace parameter_service +{ + +class ParameterService +{ + +public: + RCLCPP_MAKE_SHARED_DEFINITIONS(ParameterService); + + ParameterService(const rclcpp::node::Node::SharedPtr & node) + : node_(node) + { + get_parameters_service_ = node_->create_service( + "get_parameters_" + node_->get_name(), [&node]( + const std::shared_ptr request_header, + const std::shared_ptr request, + std::shared_ptr response) + { + auto values = node->get_parameters(request->names); + std::transform(values.cbegin(), values.cend(), std::back_inserter(response->values), + [](const rclcpp::parameter::ParameterVariant & pvariant) { + return pvariant. + get_parameter_value(); + }); + } + ); + + get_parameter_types_service_ = node_->create_service( + "get_parameter_types_" + node_->get_name(), [&node]( + const std::shared_ptr request_header, + const std::shared_ptr request, + std::shared_ptr response) + { + auto types = node->get_parameter_types(request->parameter_names); + std::transform(types.cbegin(), types.cend(), + std::back_inserter(response->parameter_types), [](const uint8_t & type) { + return static_cast(type); + }); + } + ); + + set_parameters_service_ = node_->create_service( + "set_parameters_" + node_->get_name(), [&node]( + const std::shared_ptr request_header, + const std::shared_ptr request, + std::shared_ptr response) + { + std::vector pvariants; + std::transform(request->parameters.cbegin(), request->parameters.cend(), + std::back_inserter(pvariants), + [](const rcl_interfaces::Parameter & p) { + return rclcpp::parameter::ParameterVariant:: + from_parameter(p); + }); + auto results = node->set_parameters(pvariants); + response->results = results; + } + ); + + set_parameters_atomically_service_ = + node_->create_service( + "set_parameters_atomically_" + node_->get_name(), [&node]( + const std::shared_ptr request_header, + const std::shared_ptr request, + std::shared_ptr response) + { + std::vector pvariants; + std::transform(request->parameters.cbegin(), request->parameters.cend(), + std::back_inserter(pvariants), + [](const rcl_interfaces::Parameter & p) { + return rclcpp::parameter::ParameterVariant:: + from_parameter(p); + }); + auto result = node->set_parameters_atomically(pvariants); + response->result = result; + } + ); + + describe_parameters_service_ = node_->create_service( + "describe_parameters_" + node_->get_name(), [&node]( + const std::shared_ptr request_header, + const std::shared_ptr request, + std::shared_ptr response) + { + auto descriptors = node->describe_parameters(request->names); + response->descriptors = descriptors; + } + ); + + list_parameters_service_ = node_->create_service( + "describe_parameters_" + node_->get_name(), [&node]( + const std::shared_ptr request_header, + const std::shared_ptr request, + std::shared_ptr response) + { + auto result = node->list_parameters(request->parameter_prefixes, request->depth); + response->result = result; + } + ); + + + } + +private: + const rclcpp::node::Node::SharedPtr node_; + rclcpp::service::Service::SharedPtr get_parameters_service_; + rclcpp::service::Service::SharedPtr + get_parameter_types_service_; + rclcpp::service::Service::SharedPtr set_parameters_service_; + rclcpp::service::Service::SharedPtr + set_parameters_atomically_service_; + rclcpp::service::Service::SharedPtr + describe_parameters_service_; + rclcpp::service::Service::SharedPtr list_parameters_service_; +}; + +} /* namespace parameter_service */ + +} /* namespace rclcpp */ + +#endif /* RCLCPP_RCLCPP_PARAMETER_SERVICE_HPP_ */ diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index a9d484f..35893ac 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include #include From 23e1ab4e035047e37af373ec347cc058836e2d03 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 19 May 2015 17:38:11 -0700 Subject: [PATCH 9/9] Prepend parameter methods with the node name --- rclcpp/include/rclcpp/parameter_service.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_service.hpp b/rclcpp/include/rclcpp/parameter_service.hpp index 3507fa1..c2b6ceb 100644 --- a/rclcpp/include/rclcpp/parameter_service.hpp +++ b/rclcpp/include/rclcpp/parameter_service.hpp @@ -50,7 +50,7 @@ public: : node_(node) { get_parameters_service_ = node_->create_service( - "get_parameters_" + node_->get_name(), [&node]( + node_->get_name() + "__get_parameters", [&node]( const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response) @@ -65,7 +65,7 @@ public: ); get_parameter_types_service_ = node_->create_service( - "get_parameter_types_" + node_->get_name(), [&node]( + node_->get_name() + "__get_parameter_types", [&node]( const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response) @@ -79,7 +79,7 @@ public: ); set_parameters_service_ = node_->create_service( - "set_parameters_" + node_->get_name(), [&node]( + node_->get_name() + "__set_parameters", [&node]( const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response) @@ -98,7 +98,7 @@ public: set_parameters_atomically_service_ = node_->create_service( - "set_parameters_atomically_" + node_->get_name(), [&node]( + node_->get_name() + "__set_parameters_atomically", [&node]( const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response) @@ -116,7 +116,7 @@ public: ); describe_parameters_service_ = node_->create_service( - "describe_parameters_" + node_->get_name(), [&node]( + node_->get_name() + "__describe_parameters", [&node]( const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response) @@ -127,7 +127,7 @@ public: ); list_parameters_service_ = node_->create_service( - "describe_parameters_" + node_->get_name(), [&node]( + node_->get_name() + "__describe_parameters", [&node]( const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response)