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

Get parameter map #575

Merged
merged 5 commits into from
Jan 16, 2019
Merged
Show file tree
Hide file tree
Changes from 4 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
11 changes: 11 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -401,6 +401,17 @@ if(BUILD_TESTING)
"rcl")
target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME})
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()

ament_package(
Expand Down
24 changes: 24 additions & 0 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -279,6 +279,12 @@ class Node : public std::enable_shared_from_this<Node>
const std::string & name,
const ParameterT & value);

template<typename MapValueT>
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
void
set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, MapValueT> & values);

RCLCPP_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
Expand All @@ -305,6 +311,24 @@ class Node : public std::enable_shared_from_this<Node>
bool
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".
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Regarding the signature I would rather not pass name here. Each key in the map can already be a "full" name. Otherwise this function prohibits to set two parameters in different "branches" of the "naming tree".

Same below.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

While that is true (and makes some sense for set), it doesn't really make much sense for get. If we just make it so that there is no "grouping" with this API, then there is little reason to add this API; we can do the same thing by calling get_parameters with a vector of names. The explicit purpose of the map-based one is to have a group of variables that we can get into a single map. This is similar to the map-based getParam overload in ROS1.

* This API gets all parameters that begin with name, storing them into the
* map with a key of "member" and their value. If there are no members in
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
* the named map, then the "values" argument is not changed.
*
* \param[in] name The name of the map parameter to get.
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
* \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".
/**
* If the parameter was not set, then the "value" argument is assigned
Expand Down
42 changes: 42 additions & 0 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Instead of calling get_parameter N times I would suggest to call get_parameters() once.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I can make this work using get_parameters(), but I think it is much uglier and less efficient:

template<typename MapValueT>
void
Node::set_parameter_if_not_set(
  const std::string & name,
  const std::map<std::string, MapValueT> & values)
{
  std::vector<std::string> names;

  for (const auto & val : values) {
    std::string param_name = name + "." + val.first;
    names.push_back(param_name);
  }

  std::vector<rclcpp::Parameter> params = node_parameters_->get_parameters(names);
  std::vector<rclcpp::Parameter> params_to_set;

  for (const auto & val : values) {
    std::string param_name = name + "." + val.first;
    if (std::find_if(params.begin(), params.end(),
                     [&param_name](const rclcpp::Parameter& param) {
                       return param.get_name() == param_name;
                     }) == params.end()) {
      params_to_set.push_back(rclcpp::Parameter(param_name, val.second));
    }
  }

  this->set_parameters(params_to_set);
}

This is due to the fact that get_parameters() returns only what is currently in the parameters, and silently ignores the ones that aren't there. Unless you can think of a way to reduce the number of loops and finds here, I'd prefer to stick to the current implementation.

params.push_back(rclcpp::Parameter(param_name, val.second));
}
}

this->set_parameters(params);
}

template<typename ParameterT>
bool
Node::get_parameter(const std::string & name, ParameterT & value) const
Expand All @@ -237,6 +259,26 @@ Node::get_parameter(const std::string & name, ParameterT & value) const
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>
bool
Node::get_parameter_or(
Expand Down
7 changes: 7 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,13 @@ class NodeParameters : public NodeParametersInterface
const std::string & name,
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
virtual
std::vector<rcl_interfaces::msg::ParameterDescriptor>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
#define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_

#include <map>
#include <string>
#include <vector>

Expand Down Expand Up @@ -89,6 +90,20 @@ class NodeParametersInterface
const std::string & name,
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
virtual
std::vector<rcl_interfaces::msg::ParameterDescriptor>
Expand Down
21 changes: 21 additions & 0 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
NodeParameters::describe_parameters(const std::vector<std::string> & names) const
{
Expand Down
71 changes: 71 additions & 0 deletions rclcpp/test/test_local_parameters.cpp
Original file line number Diff line number Diff line change
@@ -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;
}