diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 0305529809..94d1128910 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -73,12 +73,21 @@ class AsyncParametersClient * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe * \param[in] group (optional) The async parameter client will be added to this callback group. */ - RCLCPP_PUBLIC + template AsyncParametersClient( - const rclcpp::Node::SharedPtr node, + const std::shared_ptr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, - rclcpp::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr) + : AsyncParametersClient( + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + qos_profile, + group) + {} /// Constructor /** @@ -87,12 +96,21 @@ class AsyncParametersClient * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe * \param[in] group (optional) The async parameter client will be added to this callback group. */ - RCLCPP_PUBLIC + template AsyncParametersClient( - rclcpp::Node * node, + NodeT * node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, - rclcpp::CallbackGroup::SharedPtr group = nullptr); + rclcpp::CallbackGroup::SharedPtr group = nullptr) + : AsyncParametersClient( + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + qos_profile, + group) + {} RCLCPP_PUBLIC std::shared_future> @@ -237,31 +255,61 @@ class SyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient) - RCLCPP_PUBLIC + template explicit SyncParametersClient( - rclcpp::Node::SharedPtr node, + std::shared_ptr node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + : SyncParametersClient( + std::make_shared(), + node, + remote_node_name, + qos_profile) + {} - RCLCPP_PUBLIC + template SyncParametersClient( rclcpp::Executor::SharedPtr executor, - rclcpp::Node::SharedPtr node, + std::shared_ptr node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); - - RCLCPP_PUBLIC - explicit SyncParametersClient( - rclcpp::Node * node, + const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + : SyncParametersClient( + executor, + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + qos_profile) + {} + + template + SyncParametersClient( + NodeT * node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + : SyncParametersClient( + std::make_shared(), + node, + remote_node_name, + qos_profile) + {} - RCLCPP_PUBLIC + template SyncParametersClient( rclcpp::Executor::SharedPtr executor, - rclcpp::Node * node, + NodeT * node, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + : SyncParametersClient( + executor, + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface(), + remote_node_name, + qos_profile) + {} RCLCPP_PUBLIC SyncParametersClient( @@ -271,7 +319,18 @@ class SyncParametersClient const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string & remote_node_name = "", - const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters) + : executor_(executor), node_base_interface_(node_base_interface) + { + async_parameters_client_ = + std::make_shared( + node_base_interface, + node_topics_interface, + node_graph_interface, + node_services_interface, + remote_node_name, + qos_profile); + } RCLCPP_PUBLIC std::vector diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 03a59c6618..74c92999b0 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -99,36 +99,6 @@ AsyncParametersClient::AsyncParametersClient( node_services_interface->add_client(describe_parameters_base, group); } -AsyncParametersClient::AsyncParametersClient( - const rclcpp::Node::SharedPtr node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) -: AsyncParametersClient( - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - qos_profile, - group) -{} - -AsyncParametersClient::AsyncParametersClient( - rclcpp::Node * node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::CallbackGroup::SharedPtr group) -: AsyncParametersClient( - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - qos_profile, - group) -{} - std::shared_future> AsyncParametersClient::get_parameters( const std::vector & names, @@ -337,78 +307,6 @@ AsyncParametersClient::wait_for_service_nanoseconds(std::chrono::nanoseconds tim return true; } -SyncParametersClient::SyncParametersClient( - rclcpp::Node::SharedPtr node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) -: SyncParametersClient( - std::make_shared(), - node, - remote_node_name, - qos_profile) -{} - -SyncParametersClient::SyncParametersClient( - rclcpp::Executor::SharedPtr executor, - rclcpp::Node::SharedPtr node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) -: SyncParametersClient( - executor, - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - qos_profile) -{} - -SyncParametersClient::SyncParametersClient( - rclcpp::Node * node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) -: SyncParametersClient( - std::make_shared(), - node, - remote_node_name, - qos_profile) -{} - -SyncParametersClient::SyncParametersClient( - rclcpp::Executor::SharedPtr executor, - rclcpp::Node * node, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) -: SyncParametersClient( - executor, - node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_graph_interface(), - node->get_node_services_interface(), - remote_node_name, - qos_profile) -{} - -SyncParametersClient::SyncParametersClient( - rclcpp::Executor::SharedPtr executor, - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, - const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, - const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, - const std::string & remote_node_name, - const rmw_qos_profile_t & qos_profile) -: executor_(executor), node_base_interface_(node_base_interface) -{ - async_parameters_client_ = - std::make_shared( - node_base_interface, - node_topics_interface, - node_graph_interface, - node_services_interface, - remote_node_name, - qos_profile); -} - std::vector SyncParametersClient::get_parameters(const std::vector & parameter_names) {