Skip to content

Commit

Permalink
support regex match for parameter client
Browse files Browse the repository at this point in the history
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
  • Loading branch information
Chen Lihui committed Aug 18, 2022
1 parent 3d69031 commit 0f42d78
Show file tree
Hide file tree
Showing 6 changed files with 87 additions and 21 deletions.
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/parameter_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,12 @@ 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.
/// \param[in] node_fqn a Fully Qualified Name of node, default value is nullptr.
/// \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);
parameter_map_from_yaml_file(const std::string & yaml_filename, const char * node_fqn = nullptr);

} // namespace rclcpp

Expand Down
23 changes: 5 additions & 18 deletions rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,33 +290,20 @@ std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
AsyncParametersClient::load_parameters(
const std::string & yaml_filename)
{
rclcpp::ParameterMap parameter_map = rclcpp::parameter_map_from_yaml_file(yaml_filename);
rclcpp::ParameterMap parameter_map =
rclcpp::parameter_map_from_yaml_file(yaml_filename, remote_node_name_.c_str());
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) {
auto iter = parameter_map.find(remote_node_name_);
if (iter == parameter_map.end() || iter->second.size() == 0) {
throw rclcpp::exceptions::InvalidParametersException("No valid parameter");
}
auto future_result = set_parameters(parameters);
auto future_result = set_parameters(iter->second);

return future_result;
}
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/parameter_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value)
}

ParameterMap
rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename)
rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename, const char * node_fqn)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * rcl_parameters = rcl_yaml_node_struct_init(allocator);
Expand All @@ -153,5 +153,5 @@ rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename)
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR);
}

return rclcpp::parameter_map_from(rcl_parameters);
return rclcpp::parameter_map_from(rcl_parameters, node_fqn);
}
49 changes: 49 additions & 0 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -948,3 +948,52 @@ TEST_F(TestParameterClient, sync_parameter_load_parameters) {
auto list_parameters = synchronous_client->list_parameters({}, 3);
ASSERT_EQ(list_parameters.names.size(), static_cast<uint64_t>(5));
}

/*
Coverage for async load_parameters with complicated regex expression
*/
TEST_F(TestParameterClient, async_parameter_load_parameters_complicated_regex) {
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_complicated_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(), static_cast<uint64_t>(6));
// to check the parameter "a_value"
std::string param_name = "a_value";
auto param = load_node->get_parameter(param_name);
ASSERT_EQ(param.get_value<std::string>(), "last_one_win");
}

/*
Coverage for async load_parameters to load file without valid parameters
*/
TEST_F(TestParameterClient, async_parameter_load_no_valid_parameter) {
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" / "no_valid_parameters.yaml").string();
EXPECT_THROW(
asynchronous_client->load_parameters(parameters_filepath),
rclcpp::exceptions::InvalidParametersException);
}
25 changes: 25 additions & 0 deletions rclcpp/test/resources/test_node/load_complicated_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/**:
ros__parameters:
bar: 5
foo: 3.5
a_value: "first"

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

namespace:
load_node:
ros__parameters:
foo_bar: true
a_value: "third"

bar:
ros__parameters:
fatal: 10

/**/namespace/*:
ros__parameters:
a_value: "last_one_win"
4 changes: 4 additions & 0 deletions rclcpp/test/resources/test_node/no_valid_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/no/valid/parameters/node:
ros__parameters:
bar: 5
foo: 3.5

0 comments on commit 0f42d78

Please sign in to comment.