Skip to content

Commit

Permalink
Avoid deprecated function using another deprecated function
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Aug 17, 2022
1 parent f2ccad8 commit 5627160
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class AsyncParametersClient
node->get_node_graph_interface(),
node->get_node_services_interface(),
remote_node_name,
qos_profile,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
group)
{}

Expand Down Expand Up @@ -171,7 +171,7 @@ class AsyncParametersClient
node->get_node_graph_interface(),
node->get_node_services_interface(),
remote_node_name,
qos_profile,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
group)
{}

Expand Down Expand Up @@ -390,7 +390,7 @@ class SyncParametersClient
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node,
remote_node_name,
qos_profile)
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
Expand Down Expand Up @@ -419,7 +419,7 @@ class SyncParametersClient
node->get_node_graph_interface(),
node->get_node_services_interface(),
remote_node_name,
qos_profile)
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
Expand Down Expand Up @@ -448,7 +448,7 @@ class SyncParametersClient
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node,
remote_node_name,
qos_profile)
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
Expand Down Expand Up @@ -477,7 +477,7 @@ class SyncParametersClient
node->get_node_graph_interface(),
node->get_node_services_interface(),
remote_node_name,
qos_profile)
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
Expand Down Expand Up @@ -515,7 +515,7 @@ class SyncParametersClient
node_graph_interface,
node_services_interface,
remote_node_name,
qos_profile);
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)));
}

RCLCPP_PUBLIC
Expand Down

0 comments on commit 5627160

Please sign in to comment.