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 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
10 changes: 10 additions & 0 deletions rclcpp/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@
Changelog for package rclcpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

23.1.0 (2023-10-04)
-------------------
* Add locking to protect the TimeSource::NodeState::node_base\_ (`#2320 <https://github.com/ros2/rclcpp/issues/2320>`_)
* Update SignalHandler get_global_signal_handler to avoid complex types in static memory (`#2316 <https://github.com/ros2/rclcpp/issues/2316>`_)
* Removing Old Connext Tests (`#2313 <https://github.com/ros2/rclcpp/issues/2313>`_)
* Documentation for list_parameters (`#2315 <https://github.com/ros2/rclcpp/issues/2315>`_)
* Decouple rosout publisher init from node init. (`#2174 <https://github.com/ros2/rclcpp/issues/2174>`_)
* fix the depth to relative in list_parameters (`#2300 <https://github.com/ros2/rclcpp/issues/2300>`_)
* Contributors: Chris Lalancette, Lucas Wendland, Minju, Lee, Tomoya Fujita, Tully Foote

23.0.0 (2023-09-08)
-------------------
* Fix the return type of Rate::period. (`#2301 <https://github.com/ros2/rclcpp/issues/2301>`_)
Expand Down
82 changes: 82 additions & 0 deletions rclcpp/include/rclcpp/copy_all_parameter_values.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// 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_PARAMETER_VALUES_HPP_
#define RCLCPP__COPY_ALL_PARAMETER_VALUES_HPP_

#include <string>
#include <vector>

#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"

#include "rclcpp/parameter.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/logging.hpp"

namespace rclcpp
{

/**
* Copy all parameters from one source node to another destination node.
* May throw exceptions if parameters from source are uninitialized or undeclared.
* \param source Node to copy parameters from
* \param destination Node to copy parameters to
* \param override_existing_params Default false. Whether to override existing destination params
* if both the source and destination contain the same parameter.
*/
template<typename NodeT1, typename NodeT2>
void
copy_all_parameter_values(
const NodeT1 & source, const NodeT2 & destination, const bool override_existing_params = false)
{
using Parameters = std::vector<rclcpp::Parameter>;
using Descriptions = std::vector<rcl_interfaces::msg::ParameterDescriptor>;
auto source_params = source->get_node_parameters_interface();
auto dest_params = destination->get_node_parameters_interface();
rclcpp::Logger logger = destination->get_node_logging_interface()->get_logger();

std::vector<std::string> param_names = source_params->list_parameters({}, 0).names;
Parameters params = source_params->get_parameters(param_names);
Descriptions descriptions = source_params->describe_parameters(param_names);

for (unsigned int idx = 0; idx != params.size(); idx++) {
if (!dest_params->has_parameter(params[idx].get_name())) {
dest_params->declare_parameter(
params[idx].get_name(), params[idx].get_parameter_value(), descriptions[idx]);
} else if (override_existing_params) {
try {
rcl_interfaces::msg::SetParametersResult result =
dest_params->set_parameters_atomically({params[idx]});
if (!result.successful) {
// Parameter update rejected or read-only
RCLCPP_WARN(
logger,
"Unable to set parameter (%s): %s!",
params[idx].get_name().c_str(), result.reason.c_str());
}
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
RCLCPP_WARN(
logger,
"Unable to set parameter (%s): incompatable parameter type (%s)!",
params[idx].get_name().c_str(), e.what());
}
}
}
}

} // namespace rclcpp

#endif // RCLCPP__COPY_ALL_PARAMETER_VALUES_HPP_
11 changes: 10 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -972,7 +972,16 @@ class Node : public std::enable_shared_from_this<Node>

/// Return a list of parameters with any of the given prefixes, up to the given depth.
/**
* \todo: properly document and test this method.
* Parameters are separated into a hierarchy using the "." (dot) character.
* The "prefixes" argument is a way to select only particular parts of the hierarchy.
*
* \param[in] prefixes The list of prefixes that should be searched for within the
* current parameters. If this vector of prefixes is empty, then list_parameters
* will return all parameters.
* \param[in] depth An unsigned integer that represents the recursive depth to search.
* If this depth = 0, then all parameters that fit the prefixes will be returned.
* \returns A ListParametersResult message which contains both an array of unique prefixes
* and an array of names that were matched to the prefixes given.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::ListParametersResult
Expand Down
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_parameter_values()
* - 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_parameter_values.hpp"
#include "rclcpp/executors.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/logging.hpp"
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>rclcpp</name>
<version>23.0.0</version>
<version>23.1.0</version>
<description>The ROS client library in C++.</description>

<maintainer email="ivanpauno@ekumenlabs.com">Ivan Paunovic</maintainer>
Expand Down
45 changes: 29 additions & 16 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@

#include "rcl/arguments.h"
#include "rcl/node_type_cache.h"
#include "rcl/logging.h"
#include "rcl/logging_rosout.h"
#include "rclcpp/exceptions.hpp"
#include "rcutils/logging_macros.h"
#include "rmw/validate_namespace.h"
Expand Down Expand Up @@ -55,17 +57,12 @@ NodeBase::NodeBase(
std::shared_ptr<std::recursive_mutex> logging_mutex = get_global_logging_mutex();

rcl_ret_t ret;
{
std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
// TODO(ivanpauno): /rosout Qos should be reconfigurable.
// TODO(ivanpauno): Instead of mutually excluding rcl_node_init with the global logger mutex,
// rcl_logging_rosout_init_publisher_for_node could be decoupled from there and be called
// here directly.
ret = rcl_node_init(
rcl_node.get(),
node_name.c_str(), namespace_.c_str(),
context_->get_rcl_context().get(), &rcl_node_options);
}

// TODO(ivanpauno): /rosout Qos should be reconfigurable.
ret = rcl_node_init(
rcl_node.get(),
node_name.c_str(), namespace_.c_str(),
context_->get_rcl_context().get(), &rcl_node_options);
if (ret != RCL_RET_OK) {
if (ret == RCL_RET_NODE_INVALID_NAME) {
rcl_reset_error(); // discard rcl_node_init error
Expand Down Expand Up @@ -115,13 +112,29 @@ NodeBase::NodeBase(
throw_from_rcl_error(ret, "failed to initialize rcl node");
}

// The initialization for the rosout publisher
if (rcl_logging_rosout_enabled() && rcl_node_options.enable_rosout) {
std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
ret = rcl_logging_rosout_init_publisher_for_node(rcl_node.get());
if (ret != RCL_RET_OK) {
throw_from_rcl_error(ret, "failed to initialize rosout publisher");
}
}

node_handle_.reset(
rcl_node.release(),
[logging_mutex](rcl_node_t * node) -> void {
std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
// TODO(ivanpauno): Instead of mutually excluding rcl_node_fini with the global logger mutex,
// rcl_logging_rosout_fini_publisher_for_node could be decoupled from there and be called
// here directly.
[logging_mutex, rcl_node_options](rcl_node_t * node) -> void {
{
std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
if (rcl_logging_rosout_enabled() && rcl_node_options.enable_rosout) {
rcl_ret_t ret = rcl_logging_rosout_fini_publisher_for_node(node);
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Error in destruction of rosout publisher: %s", rcl_get_error_string().str);
}
}
}
if (rcl_node_fini(node) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1059,7 +1059,7 @@ NodeParameters::list_parameters(const std::vector<std::string> & prefixes, uint6
if (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) {
return true;
}
std::string substr = kv.first.substr(prefix.length());
std::string substr = kv.first.substr(prefix.length() + 1);
return separators_less_than_depth(substr);
}
return false;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/signal_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ SignalHandler::get_logger()
SignalHandler &
SignalHandler::get_global_signal_handler()
{
static SignalHandler signal_handler;
static SignalHandler & signal_handler = *new SignalHandler();
return signal_handler;
}

Expand Down
17 changes: 12 additions & 5 deletions rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,6 +236,7 @@ class TimeSource::NodeState final
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface)
{
std::lock_guard<std::mutex> guard(node_base_lock_);
node_base_ = node_base_interface;
node_topics_ = node_topics_interface;
node_graph_ = node_graph_interface;
Expand Down Expand Up @@ -280,17 +281,14 @@ class TimeSource::NodeState final
parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event(
node_topics_,
[this](std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event) {
if (node_base_ != nullptr) {
this->on_parameter_event(event);
}
// Do nothing if node_base_ is nullptr because it means the TimeSource is now
// without an attached node
this->on_parameter_event(event);
});
}

// Detach the attached node
void detachNode()
{
std::lock_guard<std::mutex> guard(node_base_lock_);
// destroy_clock_sub() *must* be first here, to ensure that the executor
// can't possibly call any of the callbacks as we are cleaning up.
destroy_clock_sub();
Expand Down Expand Up @@ -327,6 +325,7 @@ class TimeSource::NodeState final
std::thread clock_executor_thread_;

// Preserve the node reference
std::mutex node_base_lock_;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_{nullptr};
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_{nullptr};
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_{nullptr};
Expand Down Expand Up @@ -464,6 +463,14 @@ class TimeSource::NodeState final
// Callback for parameter updates
void on_parameter_event(std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event)
{
std::lock_guard<std::mutex> guard(node_base_lock_);

if (node_base_ == nullptr) {
// Do nothing if node_base_ is nullptr because it means the TimeSource is now
// without an attached node
return;
}

// Filter out events on 'use_sim_time' parameter instances in other nodes.
if (event->node != node_base_->get_fully_qualified_name()) {
return;
Expand Down
17 changes: 8 additions & 9 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,7 @@ if(TARGET test_exceptions)
target_link_libraries(test_exceptions ${PROJECT_NAME} mimick)
endif()

# Increasing timeout because connext can take a long time to destroy nodes
# TODO(brawner) remove when destroying Node for Connext is resolved. See:
# https://github.com/ros2/rclcpp/issues/1250
ament_add_gtest(
test_allocator_memory_strategy
strategies/test_allocator_memory_strategy.cpp
TIMEOUT 360)
ament_add_gtest(test_allocator_memory_strategy strategies/test_allocator_memory_strategy.cpp)
if(TARGET test_allocator_memory_strategy)
ament_target_dependencies(test_allocator_memory_strategy
"rcl"
Expand Down Expand Up @@ -81,6 +75,13 @@ if(TARGET test_client)
)
target_link_libraries(test_client ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_copy_all_parameter_values test_copy_all_parameter_values.cpp)
if(TARGET test_copy_all_parameter_values)
ament_target_dependencies(test_copy_all_parameter_values
"rcl_interfaces"
)
target_link_libraries(test_copy_all_parameter_values ${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 Expand Up @@ -669,8 +670,6 @@ if(TARGET test_interface_traits)
target_link_libraries(test_interface_traits ${PROJECT_NAME})
endif()

# TODO(brawner) remove when destroying Node for Connext is resolved. See:
# https://github.com/ros2/rclcpp/issues/1250
ament_add_gtest(
test_executors
executors/test_executors.cpp
Expand Down
13 changes: 10 additions & 3 deletions rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,15 +95,15 @@ TEST_F(TestNodeParameters, list_parameters)
std::find(list_result2.names.begin(), list_result2.names.end(), parameter_name),
list_result2.names.end());

// Check prefixes
// Check prefixes and the depth relative to the given prefixes
const std::string parameter_name2 = "prefix.new_parameter";
const rclcpp::ParameterValue value2(true);
const rcl_interfaces::msg::ParameterDescriptor descriptor2;
const auto added_parameter_value2 =
node_parameters->declare_parameter(parameter_name2, value2, descriptor2, false);
EXPECT_EQ(value.get<bool>(), added_parameter_value.get<bool>());
EXPECT_EQ(value2.get<bool>(), added_parameter_value2.get<bool>());
prefixes = {"prefix"};
auto list_result3 = node_parameters->list_parameters(prefixes, 2u);
auto list_result3 = node_parameters->list_parameters(prefixes, 1u);
EXPECT_EQ(1u, list_result3.names.size());
EXPECT_NE(
std::find(list_result3.names.begin(), list_result3.names.end(), parameter_name2),
Expand All @@ -116,6 +116,13 @@ TEST_F(TestNodeParameters, list_parameters)
EXPECT_NE(
std::find(list_result4.names.begin(), list_result4.names.end(), parameter_name),
list_result4.names.end());

// Return all parameters when the depth = 0
auto list_result5 = node_parameters->list_parameters(prefixes, 0u);
EXPECT_EQ(1u, list_result5.names.size());
EXPECT_NE(
std::find(list_result5.names.begin(), list_result5.names.end(), parameter_name),
list_result5.names.end());
}

TEST_F(TestNodeParameters, parameter_overrides)
Expand Down
Loading