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

support regex match for parameter client #1992

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,9 @@ class AsyncParametersClient
/**
* This function filters the parameters to be set based on the node name.
*
* If two duplicate keys exist in node names belongs to one FQN, there is no guarantee
* which one could be set.
*
* \param parameter_map named parameters to be loaded
* \return the future of the set_parameter service used to load the parameters
* \throw InvalidParametersException if there is no parameter to set
Expand Down
11 changes: 10 additions & 1 deletion rclcpp/include/rclcpp/parameter_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,20 @@ 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);

/// Get the Parameters from ParameterMap.
/// \param[in] parameter_map a parameter map.
/// \param[in] node_fqn a Fully Qualified Name of node, default value is nullptr.
/// \returns a list of a parameter
RCLCPP_PUBLIC
std::vector<Parameter>
parameters_from_map(const ParameterMap & parameter_map, const char * node_fqn = nullptr);

} // namespace rclcpp

Expand Down
28 changes: 12 additions & 16 deletions rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,28 +290,24 @@ 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);
return this->load_parameters(parameter_map);
rclcpp::ParameterMap parameter_map =
rclcpp::parameter_map_from_yaml_file(yaml_filename, remote_node_name_.c_str());

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(iter->second);

return future_result;
}

std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
AsyncParametersClient::load_parameters(
const rclcpp::ParameterMap & parameter_map)
{
std::vector<rclcpp::Parameter> parameters;
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
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);
}
}
}
std::vector<rclcpp::Parameter> parameters =
rclcpp::parameters_from_map(parameter_map, remote_node_name_.c_str());

if (parameters.size() == 0) {
throw rclcpp::exceptions::InvalidParametersException("No valid parameter");
Expand Down
31 changes: 26 additions & 5 deletions rclcpp/src/rclcpp/parameter_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,13 @@ using rclcpp::exceptions::InvalidParameterValueException;
using rclcpp::ParameterMap;
using rclcpp::ParameterValue;

static bool is_node_name_matched(const std::string & node_name, const char * node_fqn)
{
// Update the regular expression ["/*" -> "(/\\w+)" and "/**" -> "(/\\w+)*"]
std::string regex = rcpputils::find_and_replace(node_name, "/*", "(/\\w+)");
return std::regex_match(node_fqn, std::regex(regex));
}

ParameterMap
rclcpp::parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn)
{
Expand Down Expand Up @@ -53,9 +60,7 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params, const char * nod
}

if (node_fqn) {
// Update the regular expression ["/*" -> "(/\\w+)" and "/**" -> "(/\\w+)*"]
std::string regex = rcpputils::find_and_replace(node_name, "/*", "(/\\w+)");
if (!std::regex_match(node_fqn, std::regex(regex))) {
if (!is_node_name_matched(node_name, node_fqn)) {
// No need to parse the items because the user just care about node_fqn
continue;
}
Expand Down Expand Up @@ -143,7 +148,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 +158,21 @@ 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);
}

std::vector<rclcpp::Parameter>
rclcpp::parameters_from_map(const ParameterMap & parameter_map, const char * node_fqn)
{
std::vector<rclcpp::Parameter> parameters;
std::string node_name_old;
for (auto & [node_name, node_parameters] : parameter_map) {
if (node_fqn && !is_node_name_matched(node_name, node_fqn)) {
// No need to parse the items because the user just care about node_fqn
continue;
}
parameters.insert(parameters.end(), node_parameters.begin(), node_parameters.end());
}

return parameters;
}
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ if(TARGET test_init_options)
ament_target_dependencies(test_init_options "rcl")
target_link_libraries(test_init_options ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_parameter_client test_parameter_client.cpp)
ament_add_gmock(test_parameter_client test_parameter_client.cpp)
if(TARGET test_parameter_client)
ament_target_dependencies(test_parameter_client
"rcl_interfaces"
Expand Down
137 changes: 136 additions & 1 deletion rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>
#include <gmock/gmock.h>

#include <chrono>
#include <functional>
Expand Down Expand Up @@ -948,3 +948,138 @@ 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);
}

/*
Coverage for async load_parameters from maps with complicated regex expression
*/
TEST_F(TestParameterClient, async_parameter_load_parameters_from_map) {
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
rclcpp::ParameterMap parameter_map = {
{"/**",
{
{"bar", 5},
{"foo", 3.5},
{"a_value", "first"}
}
},
{"/*/load_node",
{
{"bar_foo", "ok"},
{"a_value", "second"}
}
},
{"/namespace/load_node",
{
{"foo_bar", true},
{"a_value", "third"}
}
},
{"/bar",
{
{"fatal", 10}
}
},
{"/**/namespace/*",
{
{"a_value", "not_win"}
}
}
};

auto load_future = asynchronous_client->load_parameters(parameter_map);
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);
// rclcpp::ParameterMap is an unordered map, no guarantee which value will be set for `a_value`.
EXPECT_THAT(
(std::array{"first", "second", "third", "not_win"}),
testing::Contains(param.get_value<std::string>()));
}

/*
Coverage for async load_parameters from maps without valid parameters
*/
TEST_F(TestParameterClient, async_parameter_load_from_map_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
rclcpp::ParameterMap parameter_map = {
{"/no/valid/parameters/node",
{
{"bar", 5},
{"bar", 3.5}
}
}
};
EXPECT_THROW(
asynchronous_client->load_parameters(parameter_map),
rclcpp::exceptions::InvalidParametersException);
}
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