Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create load_parameters and delete_parameters methods #1596

Merged
merged 16 commits into from
Apr 4, 2021
91 changes: 91 additions & 0 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,14 @@
#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rcl_interfaces/srv/set_parameters.hpp"
#include "rcl_interfaces/srv/set_parameters_atomically.hpp"
#include "rcl_yaml_param_parser/parser.h"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/executors.hpp"
#include "rclcpp/create_subscription.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_map.hpp"
#include "rclcpp/type_support_decl.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"
Expand Down Expand Up @@ -154,6 +157,42 @@ class AsyncParametersClient
void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
> callback = nullptr);

/// Delete several parameters at once.
/**
* This function behaves like command-line tool `ros2 param delete` would.
*
* \param parameters_names vector of parameters names
* \return the future of the set_parameter service used to delete the parameters
*/
RCLCPP_PUBLIC
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
delete_parameters(
const std::vector<std::string> & parameters_names);

/// Load parameters from yaml file.
/**
* This function behaves like command-line tool `ros2 param load` would.
*
* \param yaml_filename the full name of the yaml file
* \return the future of the set_parameter service used to load the parameters
*/
RCLCPP_PUBLIC
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
load_parameters(
const std::string & yaml_filename);

/// Load parameters from parameter map.
/**
* This function filters the parameters to be set based on the node name.
*
* \param yaml_filename the full name of the yaml file
* \return the future of the set_parameter service used to load the parameters
* \throw InvalidParametersException if there is no parameter to set
*/
RCLCPP_PUBLIC
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
load_parameters(const rclcpp::ParameterMap & parameter_map);

RCLCPP_PUBLIC
std::shared_future<rcl_interfaces::msg::ListParametersResult>
list_parameters(
Expand Down Expand Up @@ -444,6 +483,46 @@ class SyncParametersClient
);
}

/// Delete several parameters at once.
/**
* This function behaves like command-line tool `ros2 param delete` would.
*
* \param parameters_names vector of parameters names
* \param timeout for the spin used to make it synchronous
* \return the future of the set_parameter service used to delete the parameters
*/
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rcl_interfaces::msg::SetParametersResult>
delete_parameters(
const std::vector<std::string> & parameters_names,
std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
{
return delete_parameters(
parameters_names,
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
);
}

/// Load parameters from yaml file.
/**
* This function behaves like command-line tool `ros2 param load` would.
*
* \param yaml_filename the full name of the yaml file
* \param timeout for the spin used to make it synchronous
* \return the future of the set_parameter service used to load the parameters
*/
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rcl_interfaces::msg::SetParametersResult>
load_parameters(
const std::string & yaml_filename,
std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
{
return load_parameters(
yaml_filename,
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
);
}

template<typename RepT = int64_t, typename RatioT = std::milli>
rcl_interfaces::msg::ListParametersResult
list_parameters(
Expand Down Expand Up @@ -524,6 +603,18 @@ class SyncParametersClient
const std::vector<rclcpp::Parameter> & parameters,
std::chrono::nanoseconds timeout);

RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
delete_parameters(
const std::vector<std::string> & parameters_names,
std::chrono::nanoseconds timeout);

RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
load_parameters(
const std::string & yaml_filename,
std::chrono::nanoseconds timeout);
wjwwood marked this conversation as resolved.
Show resolved Hide resolved

RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(
Expand Down
9 changes: 9 additions & 0 deletions rclcpp/include/rclcpp/parameter_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__PARAMETER_MAP_HPP_
#define RCLCPP__PARAMETER_MAP_HPP_

#include <rcl_yaml_param_parser/parser.h>
#include <rcl_yaml_param_parser/types.h>

#include <string>
Expand Down Expand Up @@ -48,6 +49,14 @@ RCLCPP_PUBLIC
ParameterValue
parameter_value_from(const rcl_variant_t * const c_value);

/// Get the ParameterMap from a yaml file.
/// \param[in] yaml_filename full name of the yaml file.
/// \returns an instance of a parameter map
/// \throws from rcl error of rcl_parse_yaml_file()
RCLCPP_PUBLIC
ParameterMap
parameter_map_from_yaml_file(const std::string & yaml_filename);

} // namespace rclcpp

#endif // RCLCPP__PARAMETER_MAP_HPP_
87 changes: 86 additions & 1 deletion rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ AsyncParametersClient::AsyncParametersClient(
if (remote_node_name != "") {
remote_node_name_ = remote_node_name;
} else {
remote_node_name_ = node_base_interface->get_name();
remote_node_name_ = node_base_interface->get_fully_qualified_name();
}

rcl_client_options_t options = rcl_client_get_default_options();
Expand Down Expand Up @@ -273,6 +273,55 @@ AsyncParametersClient::set_parameters_atomically(
return future_result;
}

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
AsyncParametersClient::delete_parameters(
const std::vector<std::string> & parameters_names)
{
std::vector<rclcpp::Parameter> parameters;
for (const std::string & name : parameters_names) {
parameters.push_back(rclcpp::Parameter(name));
}
auto future_result = set_parameters(parameters);

return future_result;
}

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
AsyncParametersClient::load_parameters(
const std::string & yaml_filename)
BriceRenaudeau marked this conversation as resolved.
Show resolved Hide resolved
{
rclcpp::ParameterMap parameter_map = rclcpp::parameter_map_from_yaml_file(yaml_filename);
return this->load_parameters(parameter_map);
}

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
AsyncParametersClient::load_parameters(
const rclcpp::ParameterMap & parameter_map)
{
std::vector<rclcpp::Parameter> parameters;
std::string remote_name = remote_node_name_.substr(remote_node_name_.substr(1).find("/") + 2);
for (const auto & params : parameter_map) {
std::string node_full_name = params.first;
std::string node_name = node_full_name.substr(node_full_name.find("/*/") + 3);
if (node_full_name == remote_node_name_ ||
node_full_name == "/**" ||
(node_name == remote_name))
{
for (const auto & param : params.second) {
parameters.push_back(param);
}
}
}

if (parameters.size() == 0) {
throw rclcpp::exceptions::InvalidParametersException("No valid parameter");
}
auto future_result = set_parameters(parameters);

return future_result;
}


std::shared_future<rcl_interfaces::msg::ListParametersResult>
AsyncParametersClient::list_parameters(
const std::vector<std::string> & prefixes,
Expand Down Expand Up @@ -420,6 +469,42 @@ SyncParametersClient::set_parameters(
return std::vector<rcl_interfaces::msg::SetParametersResult>();
}

std::vector<rcl_interfaces::msg::SetParametersResult>
SyncParametersClient::delete_parameters(
const std::vector<std::string> & parameters_names,
std::chrono::nanoseconds timeout)
{
auto f = async_parameters_client_->delete_parameters(parameters_names);
wjwwood marked this conversation as resolved.
Show resolved Hide resolved

using rclcpp::executors::spin_node_until_future_complete;
if (
spin_node_until_future_complete(
*executor_, node_base_interface_, f,
timeout) == rclcpp::FutureReturnCode::SUCCESS)
{
return f.get();
}
return std::vector<rcl_interfaces::msg::SetParametersResult>();
}

std::vector<rcl_interfaces::msg::SetParametersResult>
SyncParametersClient::load_parameters(
const std::string & yaml_filename,
std::chrono::nanoseconds timeout)
{
auto f = async_parameters_client_->load_parameters(yaml_filename);

using rclcpp::executors::spin_node_until_future_complete;
if (
spin_node_until_future_complete(
*executor_, node_base_interface_, f,
timeout) == rclcpp::FutureReturnCode::SUCCESS)
{
return f.get();
}
return std::vector<rcl_interfaces::msg::SetParametersResult>();
}

rcl_interfaces::msg::SetParametersResult
SyncParametersClient::set_parameters_atomically(
const std::vector<rclcpp::Parameter> & parameters,
Expand Down
12 changes: 12 additions & 0 deletions rclcpp/src/rclcpp/parameter_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,3 +126,15 @@ rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value)

throw InvalidParameterValueException("No parameter value set");
}

ParameterMap
rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * rcl_parameters = rcl_yaml_node_struct_init(allocator);
const char * path = yaml_filename.c_str();
if (!rcl_parse_yaml_file(path, rcl_parameters)) {
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR);
}
return rclcpp::parameter_map_from(rcl_parameters);
}
89 changes: 89 additions & 0 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -861,3 +861,92 @@ TEST_F(TestParameterClient, sync_parameter_describe_parameters_allow_undeclared)
ASSERT_FALSE(parameter_descs[1].read_only);
}
}

/*
Coverage for async delete_parameters
*/
TEST_F(TestParameterClient, async_parameter_delete_parameters) {
auto asynchronous_client =
std::make_shared<rclcpp::AsyncParametersClient>(node_with_option);
// set parameter
auto set_future = asynchronous_client->set_parameters({rclcpp::Parameter("foo", 4)});
rclcpp::spin_until_future_complete(
node_with_option, set_future, std::chrono::milliseconds(100));
ASSERT_EQ(set_future.get()[0].successful, true);
// delete one parameter
auto delete_future = asynchronous_client->delete_parameters({"foo"});
rclcpp::spin_until_future_complete(
node_with_option, delete_future, std::chrono::milliseconds(100));
ASSERT_EQ(delete_future.get()[0].successful, true);
// check that deleted parameter isn't set
auto get_future2 = asynchronous_client->get_parameters({"foo"});
rclcpp::spin_until_future_complete(
node_with_option, get_future2, std::chrono::milliseconds(100));
ASSERT_EQ(
get_future2.get()[0].get_type(),
rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
}
/*
Coverage for sync delete_parameters
*/
TEST_F(TestParameterClient, sync_parameter_delete_parameters) {
auto synchronous_client =
std::make_shared<rclcpp::SyncParametersClient>(node_with_option);
// set parameter
auto set_result = synchronous_client->set_parameters({rclcpp::Parameter("foo", 4)});
// delete one parameter
auto delete_result = synchronous_client->delete_parameters({"foo"});
// check that deleted parameter isn't set
auto get_result = synchronous_client->get_parameters({"foo"});
ASSERT_EQ(
get_result[0].get_type(),
rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
}

/*
Coverage for async load_parameters
*/
TEST_F(TestParameterClient, async_parameter_load_parameters) {
auto load_node = std::make_shared<rclcpp::Node>(
"load_node",
"namespace",
rclcpp::NodeOptions().allow_undeclared_parameters(true));
auto asynchronous_client =
std::make_shared<rclcpp::AsyncParametersClient>(load_node, "/namespace/load_node");
// load parameters
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
const std::string parameters_filepath = (
test_resources_path / "test_node" / "load_parameters.yaml").string();
auto load_future = asynchronous_client->load_parameters(parameters_filepath);
auto result_code = rclcpp::spin_until_future_complete(
load_node, load_future, std::chrono::milliseconds(100));
ASSERT_EQ(result_code, rclcpp::FutureReturnCode::SUCCESS);
ASSERT_EQ(load_future.get()[0].successful, true);
// list parameters
auto list_parameters = asynchronous_client->list_parameters({}, 3);
rclcpp::spin_until_future_complete(
load_node, list_parameters, std::chrono::milliseconds(100));
ASSERT_EQ(
list_parameters.get().names.size(),
5);
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
}
/*
Coverage for sync load_parameters
*/
TEST_F(TestParameterClient, sync_parameter_load_parameters) {
auto load_node = std::make_shared<rclcpp::Node>(
"load_node",
"namespace",
rclcpp::NodeOptions().allow_undeclared_parameters(true));
auto synchronous_client =
std::make_shared<rclcpp::SyncParametersClient>(load_node);
// load parameters
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
const std::string parameters_filepath = (
test_resources_path / "test_node" / "load_parameters.yaml").string();
auto load_future = synchronous_client->load_parameters(parameters_filepath);
ASSERT_EQ(load_future[0].successful, true);
// list parameters
auto list_parameters = synchronous_client->list_parameters({}, 3);
ASSERT_EQ(list_parameters.names.size(), 5);
}
18 changes: 18 additions & 0 deletions rclcpp/test/resources/test_node/load_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/**:
ros__parameters:
bar: 5
foo: 3.5

/*:
load_node:
ros__parameters:
bar_foo: "ok"

namespace:
load_node:
ros__parameters:
foo_bar: true

bar:
ros__parameters:
fatal: 10