@@ -73,12 +73,21 @@ class AsyncParametersClient
7373 * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe
7474 * \param[in] group (optional) The async parameter client will be added to this callback group.
7575 */
76- RCLCPP_PUBLIC
76+ template < typename NodeT>
7777 AsyncParametersClient (
78- const rclcpp::Node::SharedPtr node,
78+ const std::shared_ptr<NodeT> node,
7979 const std::string & remote_node_name = " " ,
8080 const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
81- rclcpp::CallbackGroup::SharedPtr group = nullptr );
81+ rclcpp::CallbackGroup::SharedPtr group = nullptr )
82+ : AsyncParametersClient(
83+ node->get_node_base_interface (),
84+ node->get_node_topics_interface(),
85+ node->get_node_graph_interface(),
86+ node->get_node_services_interface(),
87+ remote_node_name,
88+ qos_profile,
89+ group)
90+ {}
8291
8392 // / Constructor
8493 /* *
@@ -87,12 +96,21 @@ class AsyncParametersClient
8796 * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe
8897 * \param[in] group (optional) The async parameter client will be added to this callback group.
8998 */
90- RCLCPP_PUBLIC
99+ template < typename NodeT>
91100 AsyncParametersClient (
92- rclcpp::Node * node,
101+ NodeT * node,
93102 const std::string & remote_node_name = " " ,
94103 const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
95- rclcpp::CallbackGroup::SharedPtr group = nullptr );
104+ rclcpp::CallbackGroup::SharedPtr group = nullptr )
105+ : AsyncParametersClient(
106+ node->get_node_base_interface (),
107+ node->get_node_topics_interface(),
108+ node->get_node_graph_interface(),
109+ node->get_node_services_interface(),
110+ remote_node_name,
111+ qos_profile,
112+ group)
113+ {}
96114
97115 RCLCPP_PUBLIC
98116 std::shared_future<std::vector<rclcpp::Parameter>>
@@ -237,31 +255,61 @@ class SyncParametersClient
237255public:
238256 RCLCPP_SMART_PTR_DEFINITIONS (SyncParametersClient)
239257
240- RCLCPP_PUBLIC
258+ template < typename NodeT>
241259 explicit SyncParametersClient (
242- rclcpp::Node::SharedPtr node,
260+ std::shared_ptr<NodeT> node,
243261 const std::string & remote_node_name = " " ,
244- const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
262+ const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
263+ : SyncParametersClient(
264+ std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
265+ node,
266+ remote_node_name,
267+ qos_profile)
268+ {}
245269
246- RCLCPP_PUBLIC
270+ template < typename NodeT>
247271 SyncParametersClient (
248272 rclcpp::Executor::SharedPtr executor,
249- rclcpp::Node::SharedPtr node,
273+ std::shared_ptr<NodeT> node,
250274 const std::string & remote_node_name = " " ,
251- const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
252-
253- RCLCPP_PUBLIC
254- explicit SyncParametersClient (
255- rclcpp::Node * node,
275+ const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
276+ : SyncParametersClient(
277+ executor,
278+ node->get_node_base_interface (),
279+ node->get_node_topics_interface(),
280+ node->get_node_graph_interface(),
281+ node->get_node_services_interface(),
282+ remote_node_name,
283+ qos_profile)
284+ {}
285+
286+ template <typename NodeT>
287+ SyncParametersClient (
288+ NodeT * node,
256289 const std::string & remote_node_name = " " ,
257- const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
290+ const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
291+ : SyncParametersClient(
292+ std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
293+ node,
294+ remote_node_name,
295+ qos_profile)
296+ {}
258297
259- RCLCPP_PUBLIC
298+ template < typename NodeT>
260299 SyncParametersClient (
261300 rclcpp::Executor::SharedPtr executor,
262- rclcpp::Node * node,
301+ NodeT * node,
263302 const std::string & remote_node_name = " " ,
264- const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
303+ const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
304+ : SyncParametersClient(
305+ executor,
306+ node->get_node_base_interface (),
307+ node->get_node_topics_interface(),
308+ node->get_node_graph_interface(),
309+ node->get_node_services_interface(),
310+ remote_node_name,
311+ qos_profile)
312+ {}
265313
266314 RCLCPP_PUBLIC
267315 SyncParametersClient (
@@ -271,7 +319,18 @@ class SyncParametersClient
271319 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
272320 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
273321 const std::string & remote_node_name = " " ,
274- const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
322+ const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
323+ : executor_(executor), node_base_interface_(node_base_interface)
324+ {
325+ async_parameters_client_ =
326+ std::make_shared<AsyncParametersClient>(
327+ node_base_interface,
328+ node_topics_interface,
329+ node_graph_interface,
330+ node_services_interface,
331+ remote_node_name,
332+ qos_profile);
333+ }
275334
276335 RCLCPP_PUBLIC
277336 std::vector<rclcpp::Parameter>
0 commit comments