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

Adding API to copy all parameters from one node to another #2304

Merged
merged 16 commits into from
Oct 5, 2023
Merged
Show file tree
Hide file tree
Changes from 2 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
47 changes: 47 additions & 0 deletions rclcpp/include/rclcpp/copy_all_parameters.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright 2023 Open Navigation LLC
//
// 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.

#ifndef RCLCPP__COPY_ALL_PARAMETERS_HPP_
#define RCLCPP__COPY_ALL_PARAMETERS_HPP_

#include <vector>
#include <string>
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rclcpp/parameter.hpp"
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

namespace rclcpp
{

/**
* @brief A method to copy all parameters from one node (parent) to another (child).
* May throw parameter exceptions in error conditions
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
* @param parent Node to copy parameters from
* @param child Node to copy parameters to
*/
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
template<typename NodeT1, typename NodeT2>
void copy_all_parameters(const NodeT1 & parent, const NodeT2 & child)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
{
using Parameters = std::vector<rclcpp::Parameter>;
std::vector<std::string> param_names = parent->list_parameters({}, 0).names;
Parameters params = parent->get_parameters(param_names);
for (Parameters::const_iterator iter = params.begin(); iter != params.end(); ++iter) {
if (!child->has_parameter(iter->get_name())) {
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
child->declare_parameter(iter->get_name(), iter->get_parameter_value());
}
}
}

} // namespace rclcpp

#endif // RCLCPP__COPY_ALL_PARAMETERS_HPP_
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
* - rclcpp::ParameterValue
* - rclcpp::AsyncParametersClient
* - rclcpp::SyncParametersClient
* - rclcpp::copy_all_parameters()
* - rclcpp/parameter.hpp
* - rclcpp/parameter_value.hpp
* - rclcpp/parameter_client.hpp
Expand Down Expand Up @@ -164,6 +165,7 @@
#include <csignal>
#include <memory>

#include "rclcpp/copy_all_parameters.hpp"
#include "rclcpp/executors.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/logging.hpp"
Expand Down
7 changes: 7 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,13 @@ if(TARGET test_client)
)
target_link_libraries(test_client ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_copy_all_parameters test_copy_all_parameters.cpp)
if(TARGET test_copy_all_parameters)
ament_target_dependencies(test_copy_all_parameters
"rcl_interfaces"
)
target_link_libraries(test_copy_all_parameters ${PROJECT_NAME})
endif()
ament_add_gtest(test_create_timer test_create_timer.cpp)
if(TARGET test_create_timer)
ament_target_dependencies(test_create_timer
Expand Down
57 changes: 57 additions & 0 deletions rclcpp/test/rclcpp/test_copy_all_parameters.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
// Copyright 2023 Open Navigation LLC
//
// 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 <gtest/gtest.h>
#include "rclcpp/copy_all_parameters.hpp"
#include "rclcpp/rclcpp.hpp"

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

TEST(TestParamCopying, TestParamCopying)
{
auto node1 = std::make_shared<rclcpp::Node>("test_node1");
auto node2 = std::make_shared<rclcpp::Node>("test_node2");

// Tests for (1) multiple types, (2) recursion, (3) overriding values
node1->declare_parameter("Foo1", rclcpp::ParameterValue(std::string(("bar1"))));
node1->declare_parameter("Foo2", rclcpp::ParameterValue(0.123));
node1->declare_parameter("Foo", rclcpp::ParameterValue(std::string(("bar"))));
node1->declare_parameter("Foo.bar", rclcpp::ParameterValue(std::string(("steve"))));
node2->declare_parameter("Foo", rclcpp::ParameterValue(std::string(("barz2"))));

// Show Node2 is empty of Node1's parameters, but contains its own
EXPECT_FALSE(node2->has_parameter("Foo1"));
EXPECT_FALSE(node2->has_parameter("Foo2"));
EXPECT_FALSE(node2->has_parameter("Foo.bar"));
EXPECT_TRUE(node2->has_parameter("Foo"));
EXPECT_EQ(node2->get_parameter("Foo").as_string(), std::string("barz2"));

rclcpp::copy_all_parameters(node1, node2);

// Test new parameters exist, of expected value, and original param is not overridden
EXPECT_TRUE(node2->has_parameter("Foo1"));
EXPECT_EQ(node2->get_parameter("Foo1").as_string(), std::string("bar1"));
EXPECT_TRUE(node2->has_parameter("Foo2"));
EXPECT_EQ(node2->get_parameter("Foo2").as_double(), 0.123);
EXPECT_TRUE(node2->has_parameter("Foo.bar"));
EXPECT_EQ(node2->get_parameter("Foo.bar").as_string(), std::string("steve"));
EXPECT_TRUE(node2->has_parameter("Foo"));
EXPECT_EQ(node2->get_parameter("Foo").as_string(), std::string("barz2"));
}