use the param profile for param services (#236)

* use the param profile for param services

* expose qos to users of param clients / services
This commit is contained in:
gerkey 2016-07-08 13:39:18 -07:00 committed by GitHub
parent 8251b84f68
commit ea76716982
4 changed files with 38 additions and 21 deletions

View file

@ -48,7 +48,8 @@ public:
RCLCPP_PUBLIC RCLCPP_PUBLIC
AsyncParametersClient( AsyncParametersClient(
const rclcpp::node::Node::SharedPtr node, const rclcpp::node::Node::SharedPtr node,
const std::string & remote_node_name = ""); const std::string & remote_node_name = "",
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
RCLCPP_PUBLIC RCLCPP_PUBLIC
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>> std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
@ -119,12 +120,15 @@ public:
RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient); RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient);
RCLCPP_PUBLIC RCLCPP_PUBLIC
explicit SyncParametersClient(rclcpp::node::Node::SharedPtr node); explicit SyncParametersClient(
rclcpp::node::Node::SharedPtr node,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
RCLCPP_PUBLIC RCLCPP_PUBLIC
SyncParametersClient( SyncParametersClient(
rclcpp::executor::Executor::SharedPtr executor, rclcpp::executor::Executor::SharedPtr executor,
rclcpp::node::Node::SharedPtr node); rclcpp::node::Node::SharedPtr node,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
RCLCPP_PUBLIC RCLCPP_PUBLIC
std::vector<rclcpp::parameter::ParameterVariant> std::vector<rclcpp::parameter::ParameterVariant>

View file

@ -41,7 +41,9 @@ public:
RCLCPP_SMART_PTR_DEFINITIONS(ParameterService); RCLCPP_SMART_PTR_DEFINITIONS(ParameterService);
RCLCPP_PUBLIC RCLCPP_PUBLIC
explicit ParameterService(const rclcpp::node::Node::SharedPtr node); explicit ParameterService(
const rclcpp::node::Node::SharedPtr node,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
private: private:
const rclcpp::node::Node::SharedPtr node_; const rclcpp::node::Node::SharedPtr node_;

View file

@ -23,7 +23,8 @@ using rclcpp::parameter_client::SyncParametersClient;
AsyncParametersClient::AsyncParametersClient( AsyncParametersClient::AsyncParametersClient(
const rclcpp::node::Node::SharedPtr node, const rclcpp::node::Node::SharedPtr node,
const std::string & remote_node_name) const std::string & remote_node_name,
const rmw_qos_profile_t & qos_profile)
: node_(node) : node_(node)
{ {
if (remote_node_name != "") { if (remote_node_name != "") {
@ -32,15 +33,15 @@ AsyncParametersClient::AsyncParametersClient(
remote_node_name_ = node_->get_name(); remote_node_name_ = node_->get_name();
} }
get_parameters_client_ = node_->create_client<rcl_interfaces::srv::GetParameters>( get_parameters_client_ = node_->create_client<rcl_interfaces::srv::GetParameters>(
remote_node_name_ + "__get_parameters"); remote_node_name_ + "__get_parameters", qos_profile);
get_parameter_types_client_ = node_->create_client<rcl_interfaces::srv::GetParameterTypes>( get_parameter_types_client_ = node_->create_client<rcl_interfaces::srv::GetParameterTypes>(
remote_node_name_ + "__get_parameter_types"); remote_node_name_ + "__get_parameter_types", qos_profile);
set_parameters_client_ = node_->create_client<rcl_interfaces::srv::SetParameters>( set_parameters_client_ = node_->create_client<rcl_interfaces::srv::SetParameters>(
remote_node_name_ + "__set_parameters"); remote_node_name_ + "__set_parameters", qos_profile);
list_parameters_client_ = node_->create_client<rcl_interfaces::srv::ListParameters>( list_parameters_client_ = node_->create_client<rcl_interfaces::srv::ListParameters>(
remote_node_name_ + "__list_parameters"); remote_node_name_ + "__list_parameters", qos_profile);
describe_parameters_client_ = node_->create_client<rcl_interfaces::srv::DescribeParameters>( describe_parameters_client_ = node_->create_client<rcl_interfaces::srv::DescribeParameters>(
remote_node_name_ + "__describe_parameters"); remote_node_name_ + "__describe_parameters", qos_profile);
} }
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>> std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
@ -228,19 +229,21 @@ AsyncParametersClient::list_parameters(
} }
SyncParametersClient::SyncParametersClient( SyncParametersClient::SyncParametersClient(
rclcpp::node::Node::SharedPtr node) rclcpp::node::Node::SharedPtr node,
const rmw_qos_profile_t & qos_profile)
: node_(node) : node_(node)
{ {
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>(); executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
async_parameters_client_ = std::make_shared<AsyncParametersClient>(node); async_parameters_client_ = std::make_shared<AsyncParametersClient>(node, "", qos_profile);
} }
SyncParametersClient::SyncParametersClient( SyncParametersClient::SyncParametersClient(
rclcpp::executor::Executor::SharedPtr executor, rclcpp::executor::Executor::SharedPtr executor,
rclcpp::node::Node::SharedPtr node) rclcpp::node::Node::SharedPtr node,
const rmw_qos_profile_t & qos_profile)
: executor_(executor), node_(node) : executor_(executor), node_(node)
{ {
async_parameters_client_ = std::make_shared<AsyncParametersClient>(node); async_parameters_client_ = std::make_shared<AsyncParametersClient>(node, "", qos_profile);
} }
std::vector<rclcpp::parameter::ParameterVariant> std::vector<rclcpp::parameter::ParameterVariant>

View file

@ -19,7 +19,9 @@
using rclcpp::parameter_service::ParameterService; using rclcpp::parameter_service::ParameterService;
ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node) ParameterService::ParameterService(
const rclcpp::node::Node::SharedPtr node,
const rmw_qos_profile_t & qos_profile)
: node_(node) : node_(node)
{ {
std::weak_ptr<rclcpp::node::Node> captured_node = node_; std::weak_ptr<rclcpp::node::Node> captured_node = node_;
@ -39,7 +41,8 @@ ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node)
for (auto & pvariant : values) { for (auto & pvariant : values) {
response->values.push_back(pvariant.get_parameter_value()); response->values.push_back(pvariant.get_parameter_value());
} }
} },
qos_profile
); );
get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>( get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
@ -58,7 +61,8 @@ ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node)
std::back_inserter(response->types), [](const uint8_t & type) { std::back_inserter(response->types), [](const uint8_t & type) {
return static_cast<rclcpp::parameter::ParameterType>(type); return static_cast<rclcpp::parameter::ParameterType>(type);
}); });
} },
qos_profile
); );
set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>( set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
@ -78,7 +82,8 @@ ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node)
} }
auto results = node->set_parameters(pvariants); auto results = node->set_parameters(pvariants);
response->results = results; response->results = results;
} },
qos_profile
); );
set_parameters_atomically_service_ = set_parameters_atomically_service_ =
@ -102,7 +107,8 @@ ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node)
}); });
auto result = node->set_parameters_atomically(pvariants); auto result = node->set_parameters_atomically(pvariants);
response->result = result; response->result = result;
} },
qos_profile
); );
describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>( describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
@ -118,7 +124,8 @@ ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node)
} }
auto descriptors = node->describe_parameters(request->names); auto descriptors = node->describe_parameters(request->names);
response->descriptors = descriptors; response->descriptors = descriptors;
} },
qos_profile
); );
list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>( list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
@ -134,7 +141,8 @@ ParameterService::ParameterService(const rclcpp::node::Node::SharedPtr node)
} }
auto result = node->list_parameters(request->prefixes, request->depth); auto result = node->list_parameters(request->prefixes, request->depth);
response->result = result; response->result = result;
} },
qos_profile
); );
// *INDENT-ON* // *INDENT-ON*
} }