AsyncParametersClient and get_parameter not working as expected
AsyncParametersClient and get_parameter Synchronization Issues
Description
There are synchronization issues between AsyncParametersClient::load_parameters() and Node::get_parameter() that make it difficult to reliably load and read parameters.
Problem
When loading parameters from a YAML file:
// Load parameters
parameters_client_->load_parameters(yaml_filepath_);
// Try to get updated values
get_parameter("number_particles", num_particles); // Still returns old value
Attempted solutions that don't work:
- Using futures:
auto future = parameters_client_->load_parameters(yaml_filepath_);
future.wait(); // Hangs indefinitely
- Using delays:
parameters_client_->load_parameters(yaml_filepath_);
std::this_thread::sleep_for(std::chrono::seconds(5)); // Even long delays don't help
get_parameter("number_particles", num_particles); // Still returns old value
- Double loading:
parameters_client_->load_parameters(yaml_filepath_);
parameters_client_->load_parameters(yaml_filepath_); // Try to force an update
The only way to get the updated values is to wait for another parameter event to trigger, suggesting the parameter cache isn't being properly updated.
Expected Behavior
-
load_parameters()should complete and ensure parameters are updated -
get_parameter()should return the latest values immediately after loading
Actual Behavior
-
get_parameter()returns stale values until another parameter event occurs - Futures from
load_parameters()hang indefinitely - No reliable way to synchronize parameter loading and reading
Hi, can you please provide a minimal reproducible example and also indicate which distribution of ROS 2 you are using?
You are correct in your "expectations", but last time I used this code it was working as expected.
Minimal reproduction code for ROS2 parameter loading issue
//src/minimal.cpp
#include <rclcpp/rclcpp.hpp>
#include <ament_index_cpp/get_package_share_directory.hpp>
class BasicNode : public rclcpp::Node {
public:
BasicNode() : Node("basic_node") {
// Declare parameters with default values
declare_parameter("number_particles", 200);
std::string yaml_filepath_ = ament_index_cpp::get_package_share_directory("minimal") + "/config/params.yaml";
// Create Async Parameter Client
parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this);
auto future = parameters_client_->load_parameters(yaml_filepath_);
future.wait();
get_parameter("number_particles", num_particles_);
RCLCPP_INFO_STREAM(get_logger(), "Number of particles: " << num_particles_);
}
private:
std::shared_ptr<rclcpp::AsyncParametersClient> parameters_client_;
int num_particles_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<BasicNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
config/params.yaml
minimal_node:
ros__parameters:
number_particles: 500
CMakeLists.txt
cmake_minimum_required(VERSION 3.8)
project(minimal)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(ament_index_cpp REQUIRED)
add_executable(minimal src/minimal.cpp)
ament_target_dependencies(minimal
rclcpp
ament_index_cpp
)
install(TARGETS
minimal
DESTINATION lib/${PROJECT_NAME}
)
install(DIRECTORY
config
DESTINATION share/${PROJECT_NAME}
)
ament_package()
The issue occurs when running:
ros2 run minimal minimal
^C[INFO] [1739703622.177835153] [rclcpp]: signal_handler(signum=2)
^C[INFO] [1739703623.384905111] [rclcpp]: signal_handler(signum=2)
^C[INFO] [1739703623.985758206] [rclcpp]: signal_handler(signum=2)
^C[INFO] [1739703624.235971132] [rclcpp]: signal_handler(signum=2)
Note that I can't even stop the node
And if you delete the future.wait() line if effectively loads the file, however, the get_parameter doesn't retrieve the values modified
ros2 run minimal minimal
[INFO] [1739704625.611693590] [basic_node]: Number of particles: 200
ros2 param get /basic_node number_particles
Integer value is: 100
Im using ros2 jazzy version
Hi @JavideuS, thank you a lot for the example and sorry for the wait.
There's actually a mistake in your example.
Loading parameters with an AsyncParametersClient requires the node to be spinning (that's why the API returns a future).
In your example you are doing the parameters load in the constructor, which happens before the call to rclcpp::spin(node);.
A possible fix for this would be to replace
future.wait();
with
rclcpp::spin_until_future_complete(this->get_node_base_interface(), future, std::chrono::milliseconds(100));
Alternatively, you could replace the AsyncParametersClient with a SyncParametersClient.
Then you could use the following API (which would take care internally of spinning an executor https://github.com/ros2/rclcpp/blob/rolling/rclcpp/src/rclcpp/parameter_client.cpp#L487-L502)
parameters_client_->load_parameters(yaml_filepath_, std::chrono::milliseconds(100));
Having said that, I think that this is not a very user-friendly experience.
The reason why the API behaves like this, i.e. requires a spin, to me seems because we are doing it through a parameters client object, which could be loading parameters into any arbitrary node and that does that via a set_parameters call (regardless of whether you are loading remotely or locally).
I think it would be nice to have a similar API in the node class, usable only to load parameters in that specific node itself.
auto node = std::make_shared<rclcpp::Node>("my_node");
node->load_parameters("params.yaml"); // this is non-blocking and doesn't require spinning
Any thoughts @wjwwood @fujitatomoya @mjcarroll ?