Get parameter map (#575)

* Add in the ability to get parameters in a map.

Any parameters that have a "." in them will be considered to
be part of a "map" (though they can also be get and set
individually).  This PR adds two new template specializations
to the public node API so that it can take a map, and store
the list of values (so setting the parameter with a name of
"foo" and a key of "x" will end up with a parameter of "foo.x").
It also adds an API to get all of the keys corresponding to
a prefix, and returing that as a map (so a get of "foo" will
get all parameters that begin with "foo.").  Note that all
parameters within the map must have the same type, otherwise
an rclcpp::ParameterTypeException will be thrown.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Fix style problems pointed out by uncrustify/cpplint.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Move tests for set_parameter_if_not_set/get_parameter map to rclcpp.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Rename get_parameter -> get_parameters.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Add in documentation from review.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
This commit is contained in:
Chris Lalancette 2019-01-16 14:30:12 -05:00 committed by GitHub
parent 1e91face39
commit 99dd0313ab
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
7 changed files with 199 additions and 0 deletions

View file

@ -401,6 +401,17 @@ if(BUILD_TESTING)
"rcl") "rcl")
target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME}) target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME})
endif() endif()
ament_add_gtest(test_local_parameters test/test_local_parameters.cpp)
if(TARGET test_local_parameters)
target_include_directories(test_local_parameters PUBLIC
${rcl_interfaces_INCLUDE_DIRS}
${rmw_INCLUDE_DIRS}
${rosidl_generator_cpp_INCLUDE_DIRS}
${rosidl_typesupport_cpp_INCLUDE_DIRS}
)
target_link_libraries(test_local_parameters ${PROJECT_NAME})
endif()
endif() endif()
ament_package( ament_package(

View file

@ -279,6 +279,20 @@ public:
const std::string & name, const std::string & name,
const ParameterT & value); const ParameterT & value);
/// Set a map of parameters with the same prefix.
/**
* For each key in the map, a parameter with a name of "name.key" will be set
* to the value in the map.
*
* \param[in] name The prefix of the parameters to set.
* \param[in] values The parameters to set in the given prefix.
*/
template<typename MapValueT>
void
set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, MapValueT> & values);
RCLCPP_PUBLIC RCLCPP_PUBLIC
std::vector<rclcpp::Parameter> std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const; get_parameters(const std::vector<std::string> & names) const;
@ -305,6 +319,24 @@ public:
bool bool
get_parameter(const std::string & name, ParameterT & parameter) const; get_parameter(const std::string & name, ParameterT & parameter) const;
/// Assign the value of the map parameter if set into the values argument.
/**
* Parameter names that are part of a map are of the form "name.member".
* This API gets all parameters that begin with "name", storing them into the
* map with the name of the parameter and their value.
* If there are no members in the named map, then the "values" argument is not changed.
*
* \param[in] name The prefix of the parameters to get.
* \param[out] values The map of output values, with one std::string,MapValueT
* per parameter.
* \returns true if values was changed, false otherwise
*/
template<typename MapValueT>
bool
get_parameters(
const std::string & name,
std::map<std::string, MapValueT> & values) const;
/// Get the parameter value, or the "alternative value" if not set, and assign it to "value". /// Get the parameter value, or the "alternative value" if not set, and assign it to "value".
/** /**
* If the parameter was not set, then the "value" argument is assigned * If the parameter was not set, then the "value" argument is assigned

View file

@ -224,6 +224,28 @@ Node::set_parameter_if_not_set(
} }
} }
// this is a partially-specialized version of set_parameter_if_not_set above,
// where our concrete type for ParameterT is std::map, but the to-be-determined
// type is the value in the map.
template<typename MapValueT>
void
Node::set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, MapValueT> & values)
{
std::vector<rclcpp::Parameter> params;
for (const auto & val : values) {
std::string param_name = name + "." + val.first;
rclcpp::Parameter parameter;
if (!this->get_parameter(param_name, parameter)) {
params.push_back(rclcpp::Parameter(param_name, val.second));
}
}
this->set_parameters(params);
}
template<typename ParameterT> template<typename ParameterT>
bool bool
Node::get_parameter(const std::string & name, ParameterT & value) const Node::get_parameter(const std::string & name, ParameterT & value) const
@ -237,6 +259,26 @@ Node::get_parameter(const std::string & name, ParameterT & value) const
return result; return result;
} }
// this is a partially-specialized version of get_parameter above,
// where our concrete type for ParameterT is std::map, but the to-be-determined
// type is the value in the map.
template<typename MapValueT>
bool
Node::get_parameters(
const std::string & name,
std::map<std::string, MapValueT> & values) const
{
std::map<std::string, rclcpp::Parameter> params;
bool result = node_parameters_->get_parameters_by_prefix(name, params);
if (result) {
for (const auto & param : params) {
values[param.first] = param.second.get_value<MapValueT>();
}
}
return result;
}
template<typename ParameterT> template<typename ParameterT>
bool bool
Node::get_parameter_or( Node::get_parameter_or(

View file

@ -89,6 +89,13 @@ public:
const std::string & name, const std::string & name,
rclcpp::Parameter & parameter) const; rclcpp::Parameter & parameter) const;
RCLCPP_PUBLIC
virtual
bool
get_parameters_by_prefix(
const std::string & prefix,
std::map<std::string, rclcpp::Parameter> & parameters) const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual virtual
std::vector<rcl_interfaces::msg::ParameterDescriptor> std::vector<rcl_interfaces::msg::ParameterDescriptor>

View file

@ -15,6 +15,7 @@
#ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ #ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
#define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
#include <map>
#include <string> #include <string>
#include <vector> #include <vector>
@ -89,6 +90,20 @@ public:
const std::string & name, const std::string & name,
rclcpp::Parameter & parameter) const = 0; rclcpp::Parameter & parameter) const = 0;
/// Get all parameters that have the specified prefix into the parameters map.
/*
* \param[in] prefix the name of the prefix to look for.
* \param[out] parameters a map of parameters that matched the prefix.
* \return true if any parameters with the prefix exists on the node, or
* \return false otherwise.
*/
RCLCPP_PUBLIC
virtual
bool
get_parameters_by_prefix(
const std::string & prefix,
std::map<std::string, rclcpp::Parameter> & parameters) const = 0;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual virtual
std::vector<rcl_interfaces::msg::ParameterDescriptor> std::vector<rcl_interfaces::msg::ParameterDescriptor>

View file

@ -283,6 +283,27 @@ NodeParameters::get_parameter(
} }
} }
bool
NodeParameters::get_parameters_by_prefix(
const std::string & prefix,
std::map<std::string, rclcpp::Parameter> & parameters) const
{
std::string prefix_with_dot = prefix + ".";
bool ret = false;
std::lock_guard<std::mutex> lock(mutex_);
for (const auto & param : parameters_) {
if (param.first.find(prefix_with_dot) == 0 && param.first.length() > prefix_with_dot.length()) {
// Found one!
parameters[param.first.substr(prefix_with_dot.length())] = param.second;
ret = true;
}
}
return ret;
}
std::vector<rcl_interfaces::msg::ParameterDescriptor> std::vector<rcl_interfaces::msg::ParameterDescriptor>
NodeParameters::describe_parameters(const std::vector<std::string> & names) const NodeParameters::describe_parameters(const std::vector<std::string> & names) const
{ {

View file

@ -0,0 +1,71 @@
// Copyright 2018 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <cstdio>
#include <map>
#include <string>
#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"
TEST(test_local_parameters, set_parameter_if_not_set) {
auto node = rclcpp::Node::make_shared("test_local_parameters_set_parameter_if_not_set");
{
// try to set a map of parameters
std::map<std::string, double> bar_map{
{"x", 0.5},
{"y", 1.0},
};
node->set_parameters_if_not_set("bar", bar_map);
double bar_x_value;
ASSERT_TRUE(node->get_parameter("bar.x", bar_x_value));
EXPECT_EQ(bar_x_value, 0.5);
double bar_y_value;
ASSERT_TRUE(node->get_parameter("bar.y", bar_y_value));
EXPECT_EQ(bar_y_value, 1.0);
std::map<std::string, double> new_map;
ASSERT_TRUE(node->get_parameters("bar", new_map));
ASSERT_EQ(new_map.size(), 2U);
EXPECT_EQ(new_map["x"], 0.5);
EXPECT_EQ(new_map["y"], 1.0);
}
{
// try to get a map of parameters that doesn't exist
std::map<std::string, double> no_exist_map;
ASSERT_FALSE(node->get_parameters("no_exist", no_exist_map));
}
{
// set parameters for a map with different types, then try to get them back as a map
node->set_parameter_if_not_set("baz.x", 1.0);
node->set_parameter_if_not_set("baz.y", "hello");
std::map<std::string, double> baz_map;
EXPECT_THROW(node->get_parameters("baz", baz_map), rclcpp::ParameterTypeException);
}
}
int main(int argc, char ** argv)
{
::setvbuf(stdout, NULL, _IONBF, BUFSIZ);
// NOTE: use custom main to ensure that rclcpp::init is called only once
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);
int ret = RUN_ALL_TESTS();
rclcpp::shutdown();
return ret;
}