Description
Since rclcpp::spin_some and spin_all are going to be deprecated soon #2848, I am trying to migrate it in my codebase
My use case here is:
node_ = std::make_shared<rclcpp::Node>("node");
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
executor_->add_node(node_);
parameter_client = std::make_shared<rclcpp::SyncParametersClient>(node, server_name);
auto parameters = parameter_client->get_parameters({plugin_type});
I found out that when get_parameter, it will actually call spin_node_until_future_complete, which adds, spins, and removes the node, this will cause the following error
what(): Node has already been added to an executor.
I checked the api, and parameter client actually supports passing executor in the constructor
|
SyncParametersClient( |
|
rclcpp::Executor::SharedPtr executor, |
|
std::shared_ptr<NodeT> node, |
|
const std::string & remote_node_name = "", |
|
const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS()) |
However, when getting parameters, it is always calling spin_node_until_future_complete
|
SyncParametersClient::get_parameters( |
|
const std::vector<std::string> & parameter_names, |
|
std::chrono::nanoseconds timeout) |
|
{ |
|
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) |
|
{ |
|
return f.get(); |
|
} |
|
// Return an empty vector if unsuccessful |
|
return std::vector<rclcpp::Parameter>(); |
|
} |
I am opening this issue to discuss whether it is possible to call
executor_->spin_until_future_complete(f,timeout)
when passing executor in the constructor, else call spin_node_until_future_complete
Motivation
Avoid adding node if executor passed in parameter clients
Design / Implementation Considerations
We could add a parameter for the constructor, use_internal_executor (default false), when false call rclcpp::spin_, otherwise we use the executor provided
Additional Information
No response
Description
Since rclcpp::spin_some and spin_all are going to be deprecated soon #2848, I am trying to migrate it in my codebase
My use case here is:
I found out that when get_parameter, it will actually call
spin_node_until_future_complete, which adds, spins, and removes the node, this will cause the following errorI checked the api, and parameter client actually supports passing executor in the constructor
rclcpp/rclcpp/include/rclcpp/parameter_client.hpp
Lines 318 to 322 in 82696f6
However, when getting parameters, it is always calling spin_node_until_future_complete
rclcpp/rclcpp/src/rclcpp/parameter_client.cpp
Lines 390 to 405 in 82696f6
I am opening this issue to discuss whether it is possible to call
executor_->spin_until_future_complete(f,timeout)when passing executor in the constructor, else call spin_node_until_future_complete
Motivation
Avoid adding node if executor passed in parameter clients
Design / Implementation Considerations
We could add a parameter for the constructor,
use_internal_executor(default false), when false call rclcpp::spin_, otherwise we use the executor providedAdditional Information
No response