Merge pull request #31 from ros2/developer-parameters-api
Developer parameters api
This commit is contained in:
commit
e0573d2022
4 changed files with 164 additions and 49 deletions
|
@ -95,8 +95,8 @@ public:
|
||||||
Node(std::string node_name, rclcpp::context::Context::SharedPtr context);
|
Node(std::string node_name, rclcpp::context::Context::SharedPtr context);
|
||||||
|
|
||||||
/* Get the name of the node. */
|
/* Get the name of the node. */
|
||||||
std::string
|
const std::string &
|
||||||
get_name();
|
get_name() const {return name_; }
|
||||||
|
|
||||||
/* Create and return a callback group. */
|
/* Create and return a callback group. */
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr
|
rclcpp::callback_group::CallbackGroup::SharedPtr
|
||||||
|
@ -148,23 +148,23 @@ public:
|
||||||
FunctorT callback,
|
FunctorT callback,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
||||||
|
|
||||||
const std::vector<rcl_interfaces::SetParametersResult> set_parameters(
|
std::vector<rcl_interfaces::SetParametersResult> set_parameters(
|
||||||
const std::vector<rcl_interfaces::Parameter> & parameters);
|
const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
|
||||||
|
|
||||||
const rcl_interfaces::SetParametersResult set_parameters_atomically(
|
rcl_interfaces::SetParametersResult set_parameters_atomically(
|
||||||
const std::vector<rcl_interfaces::Parameter> & parameters);
|
const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
|
||||||
|
|
||||||
const std::vector<rclcpp::parameter::ParameterVariant> get_parameters(
|
std::vector<rclcpp::parameter::ParameterVariant> get_parameters(
|
||||||
const std::vector<std::string> & names);
|
const std::vector<std::string> & names) const;
|
||||||
|
|
||||||
const std::vector<rcl_interfaces::ParameterDescriptor> describe_parameters(
|
std::vector<rcl_interfaces::ParameterDescriptor> describe_parameters(
|
||||||
const std::vector<std::string> & names);
|
const std::vector<std::string> & names) const;
|
||||||
|
|
||||||
const std::vector<uint8_t> get_parameter_types(
|
std::vector<uint8_t> get_parameter_types(
|
||||||
const std::vector<std::string> & names);
|
const std::vector<std::string> & names) const;
|
||||||
|
|
||||||
const std::vector<rcl_interfaces::ListParametersResult> list_parameters(
|
rcl_interfaces::ListParametersResult list_parameters(
|
||||||
const std::vector<std::string> & prefixes, uint64_t depth);
|
const std::vector<std::string> & prefixes, uint64_t depth) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
RCLCPP_DISABLE_COPY(Node);
|
RCLCPP_DISABLE_COPY(Node);
|
||||||
|
@ -186,7 +186,7 @@ private:
|
||||||
size_t number_of_services_;
|
size_t number_of_services_;
|
||||||
size_t number_of_clients_;
|
size_t number_of_clients_;
|
||||||
|
|
||||||
std::mutex mutex_;
|
mutable std::mutex mutex_;
|
||||||
|
|
||||||
std::map<std::string, rclcpp::parameter::ParameterVariant> parameters_;
|
std::map<std::string, rclcpp::parameter::ParameterVariant> parameters_;
|
||||||
|
|
||||||
|
|
|
@ -213,14 +213,14 @@ Node::create_service(
|
||||||
return serv;
|
return serv;
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<rcl_interfaces::SetParametersResult>
|
std::vector<rcl_interfaces::SetParametersResult>
|
||||||
Node::set_parameters(
|
Node::set_parameters(
|
||||||
const std::vector<rcl_interfaces::Parameter> & parameters)
|
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(mutex_);
|
std::lock_guard<std::mutex> lock(mutex_);
|
||||||
std::vector<rcl_interfaces::SetParametersResult> results;
|
std::vector<rcl_interfaces::SetParametersResult> results;
|
||||||
for (auto p : parameters) {
|
for (auto p : parameters) {
|
||||||
parameters_[p.name] = rclcpp::parameter::ParameterVariant::from_parameter(p);
|
parameters_[p.get_name()] = p;
|
||||||
rcl_interfaces::SetParametersResult result;
|
rcl_interfaces::SetParametersResult result;
|
||||||
result.successful = true;
|
result.successful = true;
|
||||||
// TODO: handle parameter constraints
|
// TODO: handle parameter constraints
|
||||||
|
@ -229,14 +229,14 @@ Node::set_parameters(
|
||||||
return results;
|
return results;
|
||||||
}
|
}
|
||||||
|
|
||||||
const rcl_interfaces::SetParametersResult
|
rcl_interfaces::SetParametersResult
|
||||||
Node::set_parameters_atomically(
|
Node::set_parameters_atomically(
|
||||||
const std::vector<rcl_interfaces::Parameter> & parameters)
|
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(mutex_);
|
std::lock_guard<std::mutex> lock(mutex_);
|
||||||
std::map<std::string, rclcpp::parameter::ParameterVariant> tmp_map;
|
std::map<std::string, rclcpp::parameter::ParameterVariant> tmp_map;
|
||||||
for (auto p : parameters) {
|
for (auto p : parameters) {
|
||||||
tmp_map[p.name] = rclcpp::parameter::ParameterVariant::from_parameter(p);
|
tmp_map[p.get_name()] = p;
|
||||||
}
|
}
|
||||||
tmp_map.insert(parameters_.begin(), parameters_.end());
|
tmp_map.insert(parameters_.begin(), parameters_.end());
|
||||||
std::swap(tmp_map, parameters_);
|
std::swap(tmp_map, parameters_);
|
||||||
|
@ -246,9 +246,9 @@ Node::set_parameters_atomically(
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<rclcpp::parameter::ParameterVariant>
|
std::vector<rclcpp::parameter::ParameterVariant>
|
||||||
Node::get_parameters(
|
Node::get_parameters(
|
||||||
const std::vector<std::string> & names)
|
const std::vector<std::string> & names) const
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(mutex_);
|
std::lock_guard<std::mutex> lock(mutex_);
|
||||||
std::vector<rclcpp::parameter::ParameterVariant> results;
|
std::vector<rclcpp::parameter::ParameterVariant> results;
|
||||||
|
@ -263,9 +263,9 @@ Node::get_parameters(
|
||||||
return results;
|
return results;
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<rcl_interfaces::ParameterDescriptor>
|
std::vector<rcl_interfaces::ParameterDescriptor>
|
||||||
Node::describe_parameters(
|
Node::describe_parameters(
|
||||||
const std::vector<std::string> & names)
|
const std::vector<std::string> & names) const
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(mutex_);
|
std::lock_guard<std::mutex> lock(mutex_);
|
||||||
std::vector<rcl_interfaces::ParameterDescriptor> results;
|
std::vector<rcl_interfaces::ParameterDescriptor> results;
|
||||||
|
@ -283,9 +283,9 @@ Node::describe_parameters(
|
||||||
return results;
|
return results;
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<uint8_t>
|
std::vector<uint8_t>
|
||||||
Node::get_parameter_types(
|
Node::get_parameter_types(
|
||||||
const std::vector<std::string> & names)
|
const std::vector<std::string> & names) const
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(mutex_);
|
std::lock_guard<std::mutex> lock(mutex_);
|
||||||
std::vector<uint8_t> results;
|
std::vector<uint8_t> results;
|
||||||
|
@ -302,12 +302,12 @@ Node::get_parameter_types(
|
||||||
return results;
|
return results;
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<rcl_interfaces::ListParametersResult>
|
rcl_interfaces::ListParametersResult
|
||||||
Node::list_parameters(
|
Node::list_parameters(
|
||||||
const std::vector<std::string> & prefixes, uint64_t depth)
|
const std::vector<std::string> & prefixes, uint64_t depth) const
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(mutex_);
|
std::lock_guard<std::mutex> lock(mutex_);
|
||||||
std::vector<rcl_interfaces::ListParametersResult> results;
|
rcl_interfaces::ListParametersResult result;
|
||||||
|
|
||||||
// TODO: define parameter separator, use "." for now
|
// TODO: define parameter separator, use "." for now
|
||||||
for (auto & kv : parameters_) {
|
for (auto & kv : parameters_) {
|
||||||
|
@ -320,7 +320,6 @@ Node::list_parameters(
|
||||||
return false;
|
return false;
|
||||||
}))
|
}))
|
||||||
{
|
{
|
||||||
rcl_interfaces::ListParametersResult result;
|
|
||||||
result.parameter_names.push_back(kv.first);
|
result.parameter_names.push_back(kv.first);
|
||||||
size_t last_separator = kv.first.find_last_of('.');
|
size_t last_separator = kv.first.find_last_of('.');
|
||||||
std::string prefix = kv.first.substr(0, last_separator);
|
std::string prefix = kv.first.substr(0, last_separator);
|
||||||
|
@ -329,9 +328,8 @@ Node::list_parameters(
|
||||||
{
|
{
|
||||||
result.parameter_prefixes.push_back(prefix);
|
result.parameter_prefixes.push_back(prefix);
|
||||||
}
|
}
|
||||||
results.push_back(result);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return results;
|
return result;
|
||||||
}
|
}
|
||||||
#endif /* RCLCPP_RCLCPP_NODE_IMPL_HPP_ */
|
#endif /* RCLCPP_RCLCPP_NODE_IMPL_HPP_ */
|
||||||
|
|
|
@ -190,6 +190,14 @@ public:
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
rcl_interfaces::Parameter to_parameter()
|
||||||
|
{
|
||||||
|
rcl_interfaces::Parameter parameter;
|
||||||
|
parameter.name = name_;
|
||||||
|
parameter.value = value_;
|
||||||
|
return parameter;
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::string name_;
|
std::string name_;
|
||||||
rcl_interfaces::ParameterValue value_;
|
rcl_interfaces::ParameterValue value_;
|
||||||
|
|
|
@ -46,19 +46,25 @@ class AsyncParametersClient
|
||||||
public:
|
public:
|
||||||
RCLCPP_MAKE_SHARED_DEFINITIONS(AsyncParametersClient);
|
RCLCPP_MAKE_SHARED_DEFINITIONS(AsyncParametersClient);
|
||||||
|
|
||||||
AsyncParametersClient(const rclcpp::node::Node::SharedPtr & node)
|
AsyncParametersClient(const rclcpp::node::Node::SharedPtr & node,
|
||||||
|
const std::string & remote_node_name = "")
|
||||||
: node_(node)
|
: node_(node)
|
||||||
{
|
{
|
||||||
|
if (remote_node_name != "") {
|
||||||
|
remote_node_name_ = remote_node_name;
|
||||||
|
} else {
|
||||||
|
remote_node_name_ = node_->get_name();
|
||||||
|
}
|
||||||
get_parameters_client_ = node_->create_client<rcl_interfaces::GetParameters>(
|
get_parameters_client_ = node_->create_client<rcl_interfaces::GetParameters>(
|
||||||
"get_parameters");
|
remote_node_name_ + "__get_parameters");
|
||||||
get_parameter_types_client_ = node_->create_client<rcl_interfaces::GetParameterTypes>(
|
get_parameter_types_client_ = node_->create_client<rcl_interfaces::GetParameterTypes>(
|
||||||
"get_parameter_types");
|
remote_node_name_ + "__get_parameter_types");
|
||||||
set_parameters_client_ = node_->create_client<rcl_interfaces::SetParameters>(
|
set_parameters_client_ = node_->create_client<rcl_interfaces::SetParameters>(
|
||||||
"set_parameters");
|
remote_node_name_ + "__set_parameters");
|
||||||
list_parameters_client_ = node_->create_client<rcl_interfaces::ListParameters>(
|
list_parameters_client_ = node_->create_client<rcl_interfaces::ListParameters>(
|
||||||
"list_parameters");
|
remote_node_name_ + "__list_parameters");
|
||||||
describe_parameters_client_ = node_->create_client<rcl_interfaces::DescribeParameters>(
|
describe_parameters_client_ = node_->create_client<rcl_interfaces::DescribeParameters>(
|
||||||
"describe_parameters");
|
remote_node_name_ + "__describe_parameters");
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
|
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
|
||||||
|
@ -67,8 +73,35 @@ public:
|
||||||
std::function<void(
|
std::function<void(
|
||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>)> callback = nullptr)
|
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>)> callback = nullptr)
|
||||||
{
|
{
|
||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>> f;
|
std::promise<std::vector<rclcpp::parameter::ParameterVariant>> promise_result;
|
||||||
return f;
|
auto future_result = promise_result.get_future().share();
|
||||||
|
|
||||||
|
auto request = std::make_shared<rcl_interfaces::GetParameters::Request>();
|
||||||
|
request->names = names;
|
||||||
|
|
||||||
|
get_parameters_client_->async_send_request(
|
||||||
|
request,
|
||||||
|
[&names, &promise_result, &future_result, &callback](
|
||||||
|
rclcpp::client::Client<rcl_interfaces::GetParameters>::SharedFuture cb_f) {
|
||||||
|
std::vector<rclcpp::parameter::ParameterVariant> parameter_variants;
|
||||||
|
auto & pvalues = cb_f.get()->values;
|
||||||
|
|
||||||
|
std::transform(pvalues.begin(), pvalues.end(), std::back_inserter(parameter_variants),
|
||||||
|
[&names, &pvalues](rcl_interfaces::ParameterValue pvalue) {
|
||||||
|
auto i = &pvalue - &pvalues[0];
|
||||||
|
rcl_interfaces::Parameter parameter;
|
||||||
|
parameter.name = names[i];
|
||||||
|
parameter.value = pvalue;
|
||||||
|
return rclcpp::parameter::ParameterVariant::from_parameter(parameter);
|
||||||
|
});
|
||||||
|
promise_result.set_value(parameter_variants);
|
||||||
|
if (callback != nullptr) {
|
||||||
|
callback(future_result);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
);
|
||||||
|
|
||||||
|
return future_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterType>>
|
std::shared_future<std::vector<rclcpp::parameter::ParameterType>>
|
||||||
|
@ -77,8 +110,28 @@ public:
|
||||||
std::function<void(
|
std::function<void(
|
||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterType>>)> callback = nullptr)
|
std::shared_future<std::vector<rclcpp::parameter::ParameterType>>)> callback = nullptr)
|
||||||
{
|
{
|
||||||
std::shared_future<std::vector<rclcpp::parameter::ParameterType>> f;
|
std::promise<std::vector<rclcpp::parameter::ParameterType>> promise_result;
|
||||||
return f;
|
auto future_result = promise_result.get_future().share();
|
||||||
|
|
||||||
|
auto request = std::make_shared<rcl_interfaces::GetParameterTypes::Request>();
|
||||||
|
request->parameter_names = parameter_names;
|
||||||
|
|
||||||
|
get_parameter_types_client_->async_send_request(
|
||||||
|
request,
|
||||||
|
[&promise_result, &future_result, &callback](
|
||||||
|
rclcpp::client::Client<rcl_interfaces::GetParameterTypes>::SharedFuture cb_f) {
|
||||||
|
std::vector<rclcpp::parameter::ParameterType> parameter_types;
|
||||||
|
auto & pts = cb_f.get()->parameter_types;
|
||||||
|
std::transform(pts.begin(), pts.end(), std::back_inserter(parameter_types),
|
||||||
|
[](uint8_t pt) {return static_cast<rclcpp::parameter::ParameterType>(pt); });
|
||||||
|
promise_result.set_value(parameter_types);
|
||||||
|
if (callback != nullptr) {
|
||||||
|
callback(future_result);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
);
|
||||||
|
|
||||||
|
return future_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>
|
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>
|
||||||
|
@ -87,8 +140,27 @@ public:
|
||||||
std::function<void(
|
std::function<void(
|
||||||
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>)> callback = nullptr)
|
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>)> callback = nullptr)
|
||||||
{
|
{
|
||||||
std::shared_future<std::vector<rcl_interfaces::SetParametersResult>> f;
|
std::promise<std::vector<rcl_interfaces::SetParametersResult>> promise_result;
|
||||||
return f;
|
auto future_result = promise_result.get_future().share();
|
||||||
|
|
||||||
|
auto request = std::make_shared<rcl_interfaces::SetParameters::Request>();
|
||||||
|
|
||||||
|
std::transform(parameters.begin(), parameters.end(), std::back_inserter(
|
||||||
|
request->parameters), [](
|
||||||
|
rclcpp::parameter::ParameterVariant p) {return p.to_parameter(); });
|
||||||
|
|
||||||
|
set_parameters_client_->async_send_request(
|
||||||
|
request,
|
||||||
|
[&promise_result, &future_result, &callback](
|
||||||
|
rclcpp::client::Client<rcl_interfaces::SetParameters>::SharedFuture cb_f) {
|
||||||
|
promise_result.set_value(cb_f.get()->results);
|
||||||
|
if (callback != nullptr) {
|
||||||
|
callback(future_result);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
);
|
||||||
|
|
||||||
|
return future_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_future<rcl_interfaces::SetParametersResult>
|
std::shared_future<rcl_interfaces::SetParametersResult>
|
||||||
|
@ -97,8 +169,27 @@ public:
|
||||||
std::function<void(
|
std::function<void(
|
||||||
std::shared_future<rcl_interfaces::SetParametersResult>)> callback = nullptr)
|
std::shared_future<rcl_interfaces::SetParametersResult>)> callback = nullptr)
|
||||||
{
|
{
|
||||||
std::shared_future<rcl_interfaces::SetParametersResult> f;
|
std::promise<rcl_interfaces::SetParametersResult> promise_result;
|
||||||
return f;
|
auto future_result = promise_result.get_future().share();
|
||||||
|
|
||||||
|
auto request = std::make_shared<rcl_interfaces::SetParametersAtomically::Request>();
|
||||||
|
|
||||||
|
std::transform(parameters.begin(), parameters.end(), std::back_inserter(
|
||||||
|
request->parameters), [](
|
||||||
|
rclcpp::parameter::ParameterVariant p) {return p.to_parameter(); });
|
||||||
|
|
||||||
|
set_parameters_atomically_client_->async_send_request(
|
||||||
|
request,
|
||||||
|
[&promise_result, &future_result, &callback](
|
||||||
|
rclcpp::client::Client<rcl_interfaces::SetParametersAtomically>::SharedFuture cb_f) {
|
||||||
|
promise_result.set_value(cb_f.get()->result);
|
||||||
|
if (callback != nullptr) {
|
||||||
|
callback(future_result);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
);
|
||||||
|
|
||||||
|
return future_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_future<rcl_interfaces::ListParametersResult>
|
std::shared_future<rcl_interfaces::ListParametersResult>
|
||||||
|
@ -108,8 +199,25 @@ public:
|
||||||
std::function<void(
|
std::function<void(
|
||||||
std::shared_future<rcl_interfaces::ListParametersResult>)> callback = nullptr)
|
std::shared_future<rcl_interfaces::ListParametersResult>)> callback = nullptr)
|
||||||
{
|
{
|
||||||
std::shared_future<rcl_interfaces::ListParametersResult> f;
|
std::promise<rcl_interfaces::ListParametersResult> promise_result;
|
||||||
return f;
|
auto future_result = promise_result.get_future().share();
|
||||||
|
|
||||||
|
auto request = std::make_shared<rcl_interfaces::ListParameters::Request>();
|
||||||
|
request->parameter_prefixes = parameter_prefixes;
|
||||||
|
request->depth = depth;
|
||||||
|
|
||||||
|
list_parameters_client_->async_send_request(
|
||||||
|
request,
|
||||||
|
[&promise_result, &future_result, &callback](
|
||||||
|
rclcpp::client::Client<rcl_interfaces::ListParameters>::SharedFuture cb_f) {
|
||||||
|
promise_result.set_value(cb_f.get()->result);
|
||||||
|
if (callback != nullptr) {
|
||||||
|
callback(future_result);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
);
|
||||||
|
|
||||||
|
return future_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -121,6 +229,7 @@ private:
|
||||||
set_parameters_atomically_client_;
|
set_parameters_atomically_client_;
|
||||||
rclcpp::client::Client<rcl_interfaces::ListParameters>::SharedPtr list_parameters_client_;
|
rclcpp::client::Client<rcl_interfaces::ListParameters>::SharedPtr list_parameters_client_;
|
||||||
rclcpp::client::Client<rcl_interfaces::DescribeParameters>::SharedPtr describe_parameters_client_;
|
rclcpp::client::Client<rcl_interfaces::DescribeParameters>::SharedPtr describe_parameters_client_;
|
||||||
|
std::string remote_node_name_;
|
||||||
};
|
};
|
||||||
|
|
||||||
class SyncParametersClient
|
class SyncParametersClient
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue