parameter client takes node interfaces (#368)
* parameter client takes node interfaces * correct wrong copy paste * correctly fetch node name * use node_topics_interface for creating parameter event * fix typos
This commit is contained in:
parent
2c5ab49e7c
commit
1c42a75f43
2 changed files with 99 additions and 17 deletions
|
@ -15,6 +15,7 @@
|
|||
#ifndef RCLCPP__PARAMETER_CLIENT_HPP_
|
||||
#define RCLCPP__PARAMETER_CLIENT_HPP_
|
||||
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
@ -29,6 +30,7 @@
|
|||
#include "rcl_interfaces/srv/set_parameters.hpp"
|
||||
#include "rcl_interfaces/srv/set_parameters_atomically.hpp"
|
||||
#include "rclcpp/executors.hpp"
|
||||
#include "rclcpp/create_subscription.hpp"
|
||||
#include "rclcpp/macros.hpp"
|
||||
#include "rclcpp/node.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
|
@ -46,6 +48,15 @@ class AsyncParametersClient
|
|||
public:
|
||||
RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient)
|
||||
|
||||
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 = rmw_qos_profile_parameters);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
AsyncParametersClient(
|
||||
const rclcpp::node::Node::SharedPtr node,
|
||||
|
@ -93,12 +104,29 @@ public:
|
|||
void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
|
||||
> callback = nullptr);
|
||||
|
||||
template<typename CallbackT>
|
||||
template<
|
||||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT =
|
||||
rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent, Alloc>>
|
||||
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||
on_parameter_event(CallbackT && callback)
|
||||
{
|
||||
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
||||
"parameter_events", std::forward<CallbackT>(callback), rmw_qos_profile_parameter_events);
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
auto msg_mem_strat =
|
||||
MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent, Alloc>::create_default();
|
||||
|
||||
return rclcpp::create_subscription<
|
||||
rcl_interfaces::msg::ParameterEvent, CallbackT, Alloc, SubscriptionT>(
|
||||
this->node_topics_interface_.get(),
|
||||
"parameter_events",
|
||||
std::forward<CallbackT>(callback),
|
||||
rmw_qos_profile_default,
|
||||
nullptr, // group,
|
||||
false, // ignore_local_publications,
|
||||
false, // use_intra_process_comms_,
|
||||
msg_mem_strat,
|
||||
std::make_shared<Alloc>());
|
||||
}
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -121,7 +149,7 @@ protected:
|
|||
wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
|
||||
|
||||
private:
|
||||
const rclcpp::node::Node::SharedPtr node_;
|
||||
const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
|
||||
rclcpp::client::Client<rcl_interfaces::srv::GetParameters>::SharedPtr get_parameters_client_;
|
||||
rclcpp::client::Client<rcl_interfaces::srv::GetParameterTypes>::SharedPtr
|
||||
get_parameter_types_client_;
|
||||
|
|
|
@ -25,28 +25,82 @@ using rclcpp::parameter_client::AsyncParametersClient;
|
|||
using rclcpp::parameter_client::SyncParametersClient;
|
||||
|
||||
AsyncParametersClient::AsyncParametersClient(
|
||||
const rclcpp::node::Node::SharedPtr node,
|
||||
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)
|
||||
: node_(node)
|
||||
: node_topics_interface_(node_topics_interface)
|
||||
{
|
||||
if (remote_node_name != "") {
|
||||
remote_node_name_ = remote_node_name;
|
||||
} else {
|
||||
remote_node_name_ = node_->get_name();
|
||||
remote_node_name_ = node_base_interface->get_name();
|
||||
}
|
||||
get_parameters_client_ = node_->create_client<rcl_interfaces::srv::GetParameters>(
|
||||
remote_node_name_ + "/" + parameter_service_names::get_parameters, qos_profile);
|
||||
get_parameter_types_client_ = node_->create_client<rcl_interfaces::srv::GetParameterTypes>(
|
||||
remote_node_name_ + "/" + parameter_service_names::get_parameter_types, qos_profile);
|
||||
set_parameters_client_ = node_->create_client<rcl_interfaces::srv::SetParameters>(
|
||||
remote_node_name_ + "/" + parameter_service_names::set_parameters, qos_profile);
|
||||
list_parameters_client_ = node_->create_client<rcl_interfaces::srv::ListParameters>(
|
||||
remote_node_name_ + "/" + parameter_service_names::list_parameters, qos_profile);
|
||||
describe_parameters_client_ = node_->create_client<rcl_interfaces::srv::DescribeParameters>(
|
||||
remote_node_name_ + "/" + parameter_service_names::describe_parameters, qos_profile);
|
||||
|
||||
rcl_client_options_t options = rcl_client_get_default_options();
|
||||
options.qos = qos_profile;
|
||||
|
||||
using rclcpp::client::Client;
|
||||
using rclcpp::client::ClientBase;
|
||||
|
||||
get_parameters_client_ = Client<rcl_interfaces::srv::GetParameters>::make_shared(
|
||||
node_base_interface.get(),
|
||||
node_graph_interface,
|
||||
remote_node_name_ + "/" + parameter_service_names::get_parameters,
|
||||
options);
|
||||
auto get_parameters_base = std::dynamic_pointer_cast<ClientBase>(get_parameters_client_);
|
||||
node_services_interface->add_client(get_parameters_base, nullptr);
|
||||
|
||||
get_parameter_types_client_ = Client<rcl_interfaces::srv::GetParameterTypes>::make_shared(
|
||||
node_base_interface.get(),
|
||||
node_graph_interface,
|
||||
remote_node_name_ + "/" + parameter_service_names::get_parameter_types,
|
||||
options);
|
||||
auto get_parameter_types_base =
|
||||
std::dynamic_pointer_cast<ClientBase>(get_parameter_types_client_);
|
||||
node_services_interface->add_client(get_parameter_types_base, nullptr);
|
||||
|
||||
set_parameters_client_ = Client<rcl_interfaces::srv::SetParameters>::make_shared(
|
||||
node_base_interface.get(),
|
||||
node_graph_interface,
|
||||
remote_node_name_ + "/" + parameter_service_names::set_parameters,
|
||||
options);
|
||||
auto set_parameters_base = std::dynamic_pointer_cast<ClientBase>(set_parameters_client_);
|
||||
node_services_interface->add_client(set_parameters_base, nullptr);
|
||||
|
||||
list_parameters_client_ = Client<rcl_interfaces::srv::ListParameters>::make_shared(
|
||||
node_base_interface.get(),
|
||||
node_graph_interface,
|
||||
remote_node_name_ + "/" + parameter_service_names::list_parameters,
|
||||
options);
|
||||
auto list_parameters_base = std::dynamic_pointer_cast<ClientBase>(list_parameters_client_);
|
||||
node_services_interface->add_client(list_parameters_base, nullptr);
|
||||
|
||||
describe_parameters_client_ = Client<rcl_interfaces::srv::DescribeParameters>::make_shared(
|
||||
node_base_interface.get(),
|
||||
node_graph_interface,
|
||||
remote_node_name_ + "/" + parameter_service_names::describe_parameters,
|
||||
options);
|
||||
auto describe_parameters_base =
|
||||
std::dynamic_pointer_cast<ClientBase>(describe_parameters_client_);
|
||||
node_services_interface->add_client(describe_parameters_base, nullptr);
|
||||
}
|
||||
|
||||
AsyncParametersClient::AsyncParametersClient(
|
||||
const rclcpp::node::Node::SharedPtr node,
|
||||
const std::string & remote_node_name,
|
||||
const rmw_qos_profile_t & qos_profile)
|
||||
: 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)
|
||||
{}
|
||||
|
||||
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
|
||||
AsyncParametersClient::get_parameters(
|
||||
const std::vector<std::string> & names,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue