Skip to content
Open
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
34 changes: 34 additions & 0 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -391,6 +391,33 @@ class SyncParametersClient
);
}

/// Get parameter values, reporting the wait outcome so failures are distinguishable.
/**
* Behaves like get_parameters(parameter_names, timeout), but additionally stores the
* outcome of waiting for the service response in \p result. The other overloads return
* an empty vector both when the server has no matching parameters and when the request
* does not complete (timeout or interruption); this overload lets callers tell those
* cases apart. On any non-SUCCESS result the returned vector is empty.
*
* \param[in] parameter_names the names of the parameters to get.
* \param[in] timeout how long to wait for the response before giving up.
* \param[out] result the outcome of waiting for the response.
* \return the parameter values, or an empty vector if \p result is not SUCCESS.
*/
template<typename RepT = int64_t, typename RatioT = std::milli>
std::vector<rclcpp::Parameter>
get_parameters(
const std::vector<std::string> & parameter_names,
std::chrono::duration<RepT, RatioT> timeout,
rclcpp::FutureReturnCode & result)
{
return get_parameters(
parameter_names,
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout),
result
);
}

RCLCPP_PUBLIC
bool
has_parameter(const std::string & parameter_name);
Expand Down Expand Up @@ -583,6 +610,13 @@ class SyncParametersClient
const std::vector<std::string> & parameter_names,
std::chrono::nanoseconds timeout);

RCLCPP_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(
const std::vector<std::string> & parameter_names,
std::chrono::nanoseconds timeout,
rclcpp::FutureReturnCode & result);

RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(
Expand Down
18 changes: 13 additions & 5 deletions rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -390,14 +390,22 @@ std::vector<rclcpp::Parameter>
SyncParametersClient::get_parameters(
const std::vector<std::string> & parameter_names,
std::chrono::nanoseconds timeout)
{
rclcpp::FutureReturnCode result;
return get_parameters(parameter_names, timeout, result);
}

std::vector<rclcpp::Parameter>
SyncParametersClient::get_parameters(
const std::vector<std::string> & parameter_names,
std::chrono::nanoseconds timeout,
rclcpp::FutureReturnCode & result)
{
auto f = async_parameters_client_->get_parameters(parameter_names);
using rclcpp::executors::spin_node_until_future_complete;
if (
spin_node_until_future_complete(
*executor_, node_base_interface_, f,
timeout) == rclcpp::FutureReturnCode::SUCCESS)
{
result = spin_node_until_future_complete(
*executor_, node_base_interface_, f, timeout);
if (result == rclcpp::FutureReturnCode::SUCCESS) {
return f.get();
}
// Return an empty vector if unsuccessful
Expand Down
44 changes: 44 additions & 0 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -445,6 +445,50 @@ TEST_F(TestParameterClient, sync_parameter_get_parameter_types_allow_undeclared)
/*
Coverage for sync get_parameters
*/
// Regression for ros2/rclcpp#200: the get_parameters() overload that reports the wait
// outcome lets callers distinguish a request that did not complete (TIMEOUT/INTERRUPTED)
// from a successful response that happens to be empty. The plain overload returns an
// empty vector for both, conflating the two.
TEST_F(TestParameterClient, sync_parameter_get_parameters_reports_result) {
node->declare_parameter("foo", 4);
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(node);

{
// SUCCESS with a value.
rclcpp::FutureReturnCode result;
std::vector<std::string> names{"foo"};
std::vector<rclcpp::Parameter> parameters =
synchronous_client->get_parameters(names, 10s, result);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, result);
ASSERT_EQ(1u, parameters.size());
EXPECT_EQ(4, parameters[0].as_int());
}

{
// SUCCESS but empty: the server responded, the parameter just does not exist.
rclcpp::FutureReturnCode result;
std::vector<std::string> names{"does_not_exist"};
std::vector<rclcpp::Parameter> parameters =
synchronous_client->get_parameters(names, 10s, result);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, result);
EXPECT_EQ(0u, parameters.size());
}

{
// TIMEOUT: no parameter service exists for this remote node, so the request does
// not complete. The returned vector is empty, but result distinguishes it from the
// SUCCESS-but-empty case above.
auto client_to_missing =
std::make_shared<rclcpp::SyncParametersClient>(node, "non_existent_remote_node");
rclcpp::FutureReturnCode result;
std::vector<std::string> names{"foo"};
std::vector<rclcpp::Parameter> parameters =
client_to_missing->get_parameters(names, 200ms, result);
EXPECT_EQ(rclcpp::FutureReturnCode::TIMEOUT, result);
EXPECT_EQ(0u, parameters.size());
}
}

TEST_F(TestParameterClient, sync_parameter_get_parameters) {
node->declare_parameter("foo", 4);
node->declare_parameter("bar", "this is bar");
Expand Down