Skip to content

Commit

Permalink
Make ParameterService and Sync/AsyncParameterClient accept rclcpp::QoS (
Browse files Browse the repository at this point in the history
#1978)

* Make ParameterService and Sync/AsyncParameterClient accept rclcpp::QoS

Signed-off-by: Barry Xu <barry.xu@sony.com>

* Avoid deprecated function using another deprecated function

Signed-off-by: Barry Xu <barry.xu@sony.com>

Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Sep 9, 2022
1 parent 92d4f3e commit d0e1e83
Show file tree
Hide file tree
Showing 4 changed files with 197 additions and 24 deletions.
196 changes: 177 additions & 19 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "rclcpp/node.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_map.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/type_support_decl.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"
Expand All @@ -51,14 +52,45 @@ class AsyncParametersClient
public:
RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient)

/// Create an async parameters client.
/**
* \param[in] node_base_interface The node base interface of the corresponding node.
* \param[in] node_topics_interface Node topic base interface.
* \param[in] node_graph_interface The node graph interface of the corresponding node.
* \param[in] node_services_interface Node service interface.
* \param[in] remote_node_name Name of the remote node
* \param[in] qos_profile The rmw qos profile to use to subscribe
* \param[in] group (optional) The async parameter client will be added to this callback group.
* \deprecated use rclcpp::QoS instead of rmw_qos_profile_t
*/
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
RCLCPP_PUBLIC
AsyncParametersClient(
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,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
: AsyncParametersClient(
node_base_interface,
node_topics_interface,
node_graph_interface,
node_services_interface,
remote_node_name,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
group)
{}

/// Create an async parameters client.
/**
* \param[in] node_base_interface The node base interface of the corresponding node.
* \param[in] node_topics_interface Node topic base interface.
* \param[in] node_graph_interface The node graph interface of the corresponding node.
* \param[in] node_services_interface Node service interface.
* \param[in] remote_node_name (optional) name of the remote node
* \param[in] qos_profile (optional) The rmw qos profile to use to subscribe
* \param[in] qos_profile (optional) The qos profile to use to subscribe
* \param[in] group (optional) The async parameter client will be added to this callback group.
*/
RCLCPP_PUBLIC
Expand All @@ -68,21 +100,45 @@ class AsyncParametersClient
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 rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);

/// Constructor
/**
* \param[in] node The async paramters client will be added to this node.
* \param[in] node The async parameters client will be added to this node.
* \param[in] remote_node_name name of the remote node
* \param[in] qos_profile The rmw qos profile to use to subscribe
* \param[in] group (optional) The async parameter client will be added to this callback group.
* \deprecated use rclcpp::QoS instead of rmw_qos_profile_t
*/
template<typename NodeT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
AsyncParametersClient(
const std::shared_ptr<NodeT> node,
const std::string & remote_node_name,
const rmw_qos_profile_t & qos_profile,
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,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
group)
{}

/**
* \param[in] node The async parameters client will be added to this node.
* \param[in] remote_node_name (optional) name of the remote node
* \param[in] qos_profile (optional) The rmw qos profile to use to subscribe
* \param[in] qos_profile (optional) The qos profile to use to subscribe
* \param[in] group (optional) The async parameter client will be added to this callback group.
*/
template<typename NodeT>
explicit AsyncParametersClient(
const std::shared_ptr<NodeT> node,
const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr)
: AsyncParametersClient(
node->get_node_base_interface(),
Expand All @@ -96,16 +152,40 @@ class AsyncParametersClient

/// Constructor
/**
* \param[in] node The async paramters client will be added to this node.
* \param[in] node The async parameters client will be added to this node.
* \param[in] remote_node_name Name of the remote node
* \param[in] qos_profile The rmw qos profile to use to subscribe
* \param[in] group (optional) The async parameter client will be added to this callback group.
* \deprecated use rclcpp::QoS instead of rmw_qos_profile_t
*/
template<typename NodeT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
AsyncParametersClient(
NodeT * node,
const std::string & remote_node_name,
const rmw_qos_profile_t & qos_profile,
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,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
group)
{}

/**
* \param[in] node The async parameters client will be added to this node.
* \param[in] remote_node_name (optional) name of the remote node
* \param[in] qos_profile (optional) The rmw qos profile to use to subscribe
* \param[in] qos_profile (optional) The qos profile to use to subscribe
* \param[in] group (optional) The async parameter client will be added to this callback group.
*/
template<typename NodeT>
explicit AsyncParametersClient(
NodeT * node,
const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr)
: AsyncParametersClient(
node->get_node_base_interface(),
Expand Down Expand Up @@ -211,9 +291,7 @@ class AsyncParametersClient
typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(
CallbackT && callback,
const rclcpp::QoS & qos = (
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
),
const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(),
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
))
Expand All @@ -238,9 +316,7 @@ class AsyncParametersClient
on_parameter_event(
NodeT && node,
CallbackT && callback,
const rclcpp::QoS & qos = (
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
),
const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(),
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
))
Expand Down Expand Up @@ -307,24 +383,54 @@ class SyncParametersClient
public:
RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient)

template<typename NodeT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
SyncParametersClient(
std::shared_ptr<NodeT> node,
const std::string & remote_node_name,
const rmw_qos_profile_t & qos_profile)
: SyncParametersClient(
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node,
remote_node_name,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
explicit SyncParametersClient(
std::shared_ptr<NodeT> node,
const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
: SyncParametersClient(
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node,
remote_node_name,
qos_profile)
{}

template<typename NodeT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
SyncParametersClient(
rclcpp::Executor::SharedPtr executor,
std::shared_ptr<NodeT> 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,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
SyncParametersClient(
rclcpp::Executor::SharedPtr executor,
std::shared_ptr<NodeT> node,
const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
: SyncParametersClient(
executor,
node->get_node_base_interface(),
Expand All @@ -335,24 +441,54 @@ class SyncParametersClient
qos_profile)
{}

template<typename NodeT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
SyncParametersClient(
NodeT * node,
const std::string & remote_node_name,
const rmw_qos_profile_t & qos_profile)
: SyncParametersClient(
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node,
remote_node_name,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
explicit SyncParametersClient(
NodeT * node,
const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
: SyncParametersClient(
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node,
remote_node_name,
qos_profile)
{}

template<typename NodeT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
SyncParametersClient(
rclcpp::Executor::SharedPtr executor,
NodeT * 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,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

template<typename NodeT>
SyncParametersClient(
rclcpp::Executor::SharedPtr executor,
NodeT * node,
const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
: SyncParametersClient(
executor,
node->get_node_base_interface(),
Expand All @@ -363,6 +499,28 @@ class SyncParametersClient
qos_profile)
{}

[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
RCLCPP_PUBLIC
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<AsyncParametersClient>(
node_base_interface,
node_topics_interface,
node_graph_interface,
node_services_interface,
remote_node_name,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)));
}

RCLCPP_PUBLIC
SyncParametersClient(
rclcpp::Executor::SharedPtr executor,
Expand All @@ -371,7 +529,7 @@ 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 rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
: executor_(executor), node_base_interface_(node_base_interface)
{
async_parameters_client_ =
Expand Down
19 changes: 17 additions & 2 deletions rclcpp/include/rclcpp/parameter_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"

Expand All @@ -39,12 +40,26 @@ class ParameterService
public:
RCLCPP_SMART_PTR_DEFINITIONS(ParameterService)

[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
RCLCPP_PUBLIC
explicit ParameterService(
ParameterService(
const std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
const std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
rclcpp::node_interfaces::NodeParametersInterface * node_params,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
const rmw_qos_profile_t & qos_profile)
: ParameterService(
node_base,
node_services,
node_params,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)))
{}

RCLCPP_PUBLIC
ParameterService(
const std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
const std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
rclcpp::node_interfaces::NodeParametersInterface * node_params,
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS());

private:
rclcpp::Service<rcl_interfaces::srv::GetParameters>::SharedPtr get_parameters_service_;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ AsyncParametersClient::AsyncParametersClient(
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,
const rclcpp::QoS & qos_profile,
rclcpp::CallbackGroup::SharedPtr group)
: node_topics_interface_(node_topics_interface)
{
Expand All @@ -46,7 +46,7 @@ AsyncParametersClient::AsyncParametersClient(
}

rcl_client_options_t options = rcl_client_get_default_options();
options.qos = qos_profile;
options.qos = qos_profile.get_rmw_qos_profile();

using rclcpp::Client;
using rclcpp::ClientBase;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/parameter_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ ParameterService::ParameterService(
const std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base,
const std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services,
rclcpp::node_interfaces::NodeParametersInterface * node_params,
const rmw_qos_profile_t & qos_profile)
const rclcpp::QoS & qos_profile)
{
const std::string node_name = node_base->get_name();

Expand Down

0 comments on commit d0e1e83

Please sign in to comment.