Skip to content

Commit

Permalink
Refactored get_param to use get_params. Renamed param to parameter. U…
Browse files Browse the repository at this point in the history
…pdate code to latest rcl_interfaces
  • Loading branch information
Esteve Fernandez committed Apr 16, 2015
1 parent b11245f commit 333cfe6
Show file tree
Hide file tree
Showing 3 changed files with 161 additions and 153 deletions.
37 changes: 19 additions & 18 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,29 +122,30 @@ class Node

template <typename ParamTypeT>
std::shared_future<ParamTypeT>
async_get_param(
const std::string& node_name, const parameter::ParamName& key,
async_get_parameter(
const std::string& node_name, const parameter::ParameterName& key,
std::function<void(std::shared_future<ParamTypeT>)> callback=nullptr);

std::shared_future< std::vector<parameter::ParamContainer> >
async_get_params(
const std::string& node_name, const std::vector<parameter::ParamName>& parameter_names,
std::function<void(std::shared_future<std::vector<parameter::ParamContainer> >)> callback=nullptr);
std::shared_future< std::vector<parameter::ParameterContainer> >
async_get_parameters(
const std::string& node_name, const std::vector<parameter::ParameterName>& parameter_names,
std::function<void(std::shared_future<std::vector<parameter::ParameterContainer> >)> callback=nullptr);

std::shared_future<bool>
async_has_param(const std::string& node_name, const parameter::ParamQuery& query,
std::function<void(std::shared_future<bool>)> callback=nullptr);
async_has_parameter(
const std::string& node_name, const parameter::ParameterQuery& query,
std::function<void(std::shared_future<bool>)> callback=nullptr);

template <typename ParamTypeT>
std::shared_future<bool>
async_set_param(
const std::string& node_name, const parameter::ParamName& key,
async_set_parameter(
const std::string& node_name, const parameter::ParameterName& key,
const ParamTypeT& value, std::function<void(std::shared_future<bool>)> callback=nullptr);

std::shared_future<bool>
async_set_params(
async_set_parameters(
const std::string& node_name,
const std::vector<parameter::ParamContainer>& key_values,
const std::vector<parameter::ParameterContainer>& key_values,
std::function<void(std::shared_future<bool>)> callback=nullptr);

private:
Expand All @@ -167,19 +168,19 @@ class Node
size_t number_of_services_;
size_t number_of_clients_;

std::map<parameter::ParamName, parameter::ParamContainer> params_;
std::map<parameter::ParameterName, parameter::ParameterContainer> params_;

template <typename ParamTypeT>
ParamTypeT get_param(const parameter::ParamName& key) const;
ParamTypeT get_parameter(const parameter::ParameterName& key) const;

std::vector<parameter::ParamContainer>
get_params(const std::vector<parameter::ParamQuery>& query) const;
std::vector<parameter::ParameterContainer>
get_parameters(const std::vector<parameter::ParameterQuery>& query) const;

bool
has_param(const parameter::ParamQuery& query) const;
has_parameter(const parameter::ParameterQuery& query) const;

template <typename ParamTypeT>
void set_param(const parameter::ParamName& key, const ParamTypeT& value);
void set_parameter(const parameter::ParameterName& key, const ParamTypeT& value);
};

} /* namespace node */
Expand Down
169 changes: 90 additions & 79 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,11 @@

#include <rclcpp/contexts/default_context.hpp>

#include <rcl_interfaces/GetParams.h>
#include <rcl_interfaces/HasParam.h>
#include <rcl_interfaces/Param.h>
#include <rcl_interfaces/ParamDescription.h>
#include <rcl_interfaces/SetParams.h>
#include <rcl_interfaces/GetParameters.h>
#include <rcl_interfaces/HasParameters.h>
#include <rcl_interfaces/Parameter.h>
#include <rcl_interfaces/ParameterDescription.h>
#include <rcl_interfaces/SetParameters.h>

#ifndef RCLCPP_RCLCPP_NODE_HPP_
#include "node.hpp"
Expand Down Expand Up @@ -229,35 +229,35 @@ Node::create_service(

template <typename ParamTypeT>
ParamTypeT
Node::get_param(const parameter::ParamName& key) const
Node::get_parameter(const parameter::ParameterName& key) const
{
const parameter::ParamContainer pc(this->params_.at(key));
const parameter::ParameterContainer pc(this->params_.at(key));
return pc.get_value<ParamTypeT>();
}

template <typename ParamTypeT>
void
Node::set_param(const parameter::ParamName& key, const ParamTypeT& value)
Node::set_parameter(const parameter::ParameterName& key, const ParamTypeT& value)
{
parameter::ParamContainer pc(key, value);
parameter::ParameterContainer pc(key, value);
params_[key] = pc;
}

bool
Node::has_param(const parameter::ParamQuery& query) const
Node::has_parameter(const parameter::ParameterQuery& query) const
{
const parameter::ParamName key = query.get_name();
const parameter::ParameterName key = query.get_name();
return (params_.find(key) != params_.end());
}

std::vector<parameter::ParamContainer>
Node::get_params(const std::vector<parameter::ParamQuery>& queries) const
std::vector<parameter::ParameterContainer>
Node::get_parameters(const std::vector<parameter::ParameterQuery>& queries) const
{
std::vector<parameter::ParamContainer> result;
std::vector<parameter::ParameterContainer> result;

for(auto& kv: params_) {
if(std::any_of(queries.cbegin(), queries.cend(),
[&kv](const parameter::ParamQuery& query) {
[&kv](const parameter::ParameterQuery& query) {
return kv.first == query.get_name();})) {
result.push_back(kv.second);
}
Expand All @@ -267,89 +267,96 @@ Node::get_params(const std::vector<parameter::ParamQuery>& queries) const

template <typename ParamTypeT>
std::shared_future<ParamTypeT>
Node::async_get_param(
const std::string& node_name, const parameter::ParamName& key,
Node::async_get_parameter(
const std::string& node_name, const parameter::ParameterName& key,
std::function<void(std::shared_future<ParamTypeT>)> callback)
{
std::promise<ParamTypeT> promise_result;
auto future_result = promise_result.get_future().share();
std::vector<parameter::ParamName> param_names = {{ key }};
std::vector<parameter::ParameterName> param_names = {{ key }};

this->async_get_params(
this->async_get_parameters(
node_name, param_names,
[&promise_result, &future_result, &callback, &param_names](
std::shared_future<std::vector<parameter::ParamContainer> >) {});

std::shared_future<std::vector<parameter::ParameterContainer> > cb_f) {
promise_result.set_value(cb_f.get()[0].get_value<ParamTypeT>());
if(callback != nullptr) {
callback(future_result);
}
});

return future_result;
}


std::shared_future< std::vector<parameter::ParamContainer> >
Node::async_get_params(
const std::string& node_name, const std::vector<parameter::ParamName>& parameter_names,
std::function<void(std::shared_future<std::vector<parameter::ParamContainer> >)> callback)
std::shared_future< std::vector<parameter::ParameterContainer> >
Node::async_get_parameters(
const std::string& node_name, const std::vector<parameter::ParameterName>& parameter_names,
std::function<void(std::shared_future<std::vector<parameter::ParameterContainer> >)> callback)
{
std::promise< std::vector<parameter::ParamContainer> > promise_result;
std::promise< std::vector<parameter::ParameterContainer> > promise_result;
auto future_result = promise_result.get_future().share();
if (node_name == this->get_name()) {
std::vector<parameter::ParamContainer> value;
std::vector<parameter::ParameterContainer> value;
for(auto pn : parameter_names) {
if (this->has_param(pn)) {
if (this->has_parameter(pn)) {
try {
parameter::ParamContainer param_container(pn, this->get_param<int64_t>(pn));
parameter::ParameterContainer param_container(pn, this->get_parameter<int64_t>(pn));
value.push_back(param_container);
// TODO: use custom exception
} catch(...) {
try {
parameter::ParamContainer param_container(pn, this->get_param<double>(pn));
parameter::ParameterContainer param_container(pn, this->get_parameter<double>(pn));
value.push_back(param_container);
} catch(...) {
try {
parameter::ParamContainer param_container(pn, this->get_param<std::string>(pn));
parameter::ParameterContainer param_container(pn, this->get_parameter<std::string>(pn));
value.push_back(param_container);
} catch(...) {
parameter::ParamContainer param_container(pn, this->get_param<bool>(pn));
parameter::ParameterContainer param_container(pn, this->get_parameter<bool>(pn));
value.push_back(param_container);
}
}
}
}
}
promise_result.set_value(value);
if (callback != nullptr) {
callback(future_result);
}
} else {
auto client = this->create_client<rcl_interfaces::GetParams>("get_params");
auto request = std::make_shared<rcl_interfaces::GetParams::Request>();
auto client = this->create_client<rcl_interfaces::GetParameters>("get_params");
auto request = std::make_shared<rcl_interfaces::GetParameters::Request>();
for(auto parameter_name : parameter_names) {
rcl_interfaces::ParamDescription description;
rcl_interfaces::ParameterDescription description;
description.name = parameter_name;
request->param_descriptions.push_back(description);
request->parameter_descriptions.push_back(description);
}

client->async_send_request(
request, [&promise_result, &future_result, &callback] (
rclcpp::client::Client<rcl_interfaces::GetParams>::SharedFuture cb_f) {
std::vector<parameter::ParamContainer> value;
rclcpp::client::Client<rcl_interfaces::GetParameters>::SharedFuture cb_f) {
std::vector<parameter::ParameterContainer> value;
auto parameters = cb_f.get()->parameters;
for(auto parameter : parameters) {
switch(parameter.description.param_type) {
case rcl_interfaces::ParamDescription::BOOL_PARAM:
value.push_back(parameter::ParamContainer(
switch(parameter.description.parameter_type) {
case rcl_interfaces::ParameterDescription::BOOL_PARAMETER:
value.push_back(parameter::ParameterContainer(
parameter.description.name,
rclcpp::parameter::get_parameter_value<bool>(parameter)));
break;
case rcl_interfaces::ParamDescription::STRING_PARAM:
value.push_back(parameter::ParamContainer(
case rcl_interfaces::ParameterDescription::STRING_PARAMETER:
value.push_back(parameter::ParameterContainer(
parameter.description.name,
rclcpp::parameter::get_parameter_value<std::string>(parameter)));
break;
case rcl_interfaces::ParamDescription::DOUBLE_PARAM:
value.push_back(parameter::ParamContainer(
case rcl_interfaces::ParameterDescription::DOUBLE_PARAMETER:
value.push_back(parameter::ParameterContainer(
parameter.description.name,
rclcpp::parameter::get_parameter_value<double>(parameter)));
break;
case rcl_interfaces::ParamDescription::INTEGER_PARAM:
value.push_back(parameter::ParamContainer(
case rcl_interfaces::ParameterDescription::INTEGER_PARAMETER:
value.push_back(parameter::ParameterContainer(
parameter.description.name,
rclcpp::parameter::get_parameter_value<int64_t>(parameter)));
break;
Expand All @@ -369,53 +376,56 @@ Node::async_get_params(
}

std::shared_future<bool>
Node::async_set_params(
Node::async_set_parameters(
const std::string& node_name,
const std::vector<parameter::ParamContainer>& key_values,
const std::vector<parameter::ParameterContainer>& key_values,
std::function<void(std::shared_future<bool>)> callback)
{
std::promise<bool> promise_result;
auto future_result = promise_result.get_future().share();
if (node_name == this->get_name()) {
for(auto kv : key_values) {
switch(kv.get_typeID()) {
case parameter::ParamDataType::INT_PARAM:
this->set_param(kv.get_name(), kv.get_value<int64_t>());
case parameter::ParameterDataType::INTEGER_PARAMETER:
this->set_parameter(kv.get_name(), kv.get_value<int64_t>());
break;
case parameter::ParamDataType::DOUBLE_PARAM:
this->set_param(kv.get_name(), kv.get_value<double>());
case parameter::ParameterDataType::DOUBLE_PARAMETER:
this->set_parameter(kv.get_name(), kv.get_value<double>());
break;
case parameter::ParamDataType::STRING_PARAM:
this->set_param(kv.get_name(), kv.get_value<std::string>());
case parameter::ParameterDataType::STRING_PARAMETER:
this->set_parameter(kv.get_name(), kv.get_value<std::string>());
break;
case parameter::ParamDataType::BOOL_PARAM:
this->set_param(kv.get_name(), kv.get_value<bool>());
case parameter::ParameterDataType::BOOL_PARAMETER:
this->set_parameter(kv.get_name(), kv.get_value<bool>());
break;
default:
throw std::runtime_error("Invalid parameter type");
}
}
promise_result.set_value(true);
if (callback != nullptr) {
callback(future_result);
}
} else {
auto client = this->create_client<rcl_interfaces::SetParams>("set_params");
auto request = std::make_shared<rcl_interfaces::SetParams::Request>();
auto client = this->create_client<rcl_interfaces::SetParameters>("set_params");
auto request = std::make_shared<rcl_interfaces::SetParameters::Request>();
for (auto kv: key_values) {
rcl_interfaces::Param parameter;
rcl_interfaces::Parameter parameter;
parameter.description.name = kv.get_name();
switch(kv.get_typeID()) {
case parameter::ParamDataType::INT_PARAM:
case parameter::ParameterDataType::INTEGER_PARAMETER:
rclcpp::parameter::set_parameter_value<int64_t>(
parameter, kv.get_value<int64_t>());
break;
case parameter::ParamDataType::DOUBLE_PARAM:
case parameter::ParameterDataType::DOUBLE_PARAMETER:
rclcpp::parameter::set_parameter_value<double>(
parameter, kv.get_value<double>());
break;
case parameter::ParamDataType::STRING_PARAM:
case parameter::ParameterDataType::STRING_PARAMETER:
rclcpp::parameter::set_parameter_value<std::string>(
parameter, kv.get_value<std::string>());
break;
case parameter::ParamDataType::BOOL_PARAM:
case parameter::ParameterDataType::BOOL_PARAMETER:
rclcpp::parameter::set_parameter_value<bool>(
parameter, kv.get_value<bool>());
break;
Expand All @@ -427,7 +437,7 @@ Node::async_set_params(

client->async_send_request(
request, [&promise_result, &future_result, &callback] (
rclcpp::client::Client<rcl_interfaces::SetParams>::SharedFuture cb_f) {
rclcpp::client::Client<rcl_interfaces::SetParameters>::SharedFuture cb_f) {
promise_result.set_value(cb_f.get()->success);
if (callback != nullptr) {
callback(future_result);
Expand All @@ -440,33 +450,34 @@ Node::async_set_params(

template <typename ParamTypeT>
std::shared_future<bool>
Node::async_set_param(
const std::string& node_name, const parameter::ParamName& key, const ParamTypeT& value,
Node::async_set_parameter(
const std::string& node_name, const parameter::ParameterName& key, const ParamTypeT& value,
std::function<void(std::shared_future<bool>)> callback)
{
std::vector<parameter::ParamContainer> param_containers;
parameter::ParamContainer param_container(key, value);
param_containers.push_back(param_container);
return this->async_set_params(node_name, param_containers, callback);
std::vector<parameter::ParameterContainer> param_containers = {{
parameter::ParameterContainer(key, value) }};
return this->async_set_parameters(node_name, param_containers, callback);
}

std::shared_future<bool>
Node::async_has_param(
const std::string& node_name, const parameter::ParamQuery& query,
Node::async_has_parameter(
const std::string& node_name, const parameter::ParameterQuery& query,
std::function<void(std::shared_future<bool>)> callback)
{
std::promise<bool> promise_result;
auto future_result = promise_result.get_future().share();
if (node_name == this->get_name()) {
promise_result.set_value(this->has_param(query));
promise_result.set_value(this->has_parameter(query));
} else {
auto client = this->create_client<rcl_interfaces::HasParam>("has_param");
auto request = std::make_shared<rcl_interfaces::HasParam::Request>();
request->param_description.name = query.get_name();
auto client = this->create_client<rcl_interfaces::HasParameters>("has_params");
auto request = std::make_shared<rcl_interfaces::HasParameters::Request>();
rcl_interfaces::ParameterDescription parameter_description;
parameter_description.name = query.get_name();
request->parameter_descriptions.push_back(parameter_description);
client->async_send_request(
request, [&promise_result, &future_result, &callback] (
rclcpp::client::Client<rcl_interfaces::HasParam>::SharedFuture cb_f) {
promise_result.set_value(cb_f.get()->result);
rclcpp::client::Client<rcl_interfaces::HasParameters>::SharedFuture cb_f) {
promise_result.set_value(cb_f.get()->result[0]);
if (callback != nullptr) {
callback(future_result);
}
Expand Down
Loading

0 comments on commit 333cfe6

Please sign in to comment.