From c339fbaea72abceb01463d7af4cc80490fa8af35 Mon Sep 17 00:00:00 2001 From: Stephanie Eng Date: Fri, 13 Mar 2026 16:41:34 -0400 Subject: [PATCH] Use a separate node for the srv IK client --- .../srv_kinematics_plugin.hpp | 4 ++++ .../src/srv_kinematics_plugin.cpp | 14 +++++++++----- 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.hpp b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.hpp index 6a2f11da4a..dce54dfa96 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.hpp +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.hpp @@ -42,6 +42,7 @@ #pragma once // ROS2 +#include #include // System @@ -150,6 +151,9 @@ class SrvKinematicsPlugin : public kinematics::KinematicsBase int num_possible_redundant_joints_; rclcpp::Client::SharedPtr ik_service_client_; + rclcpp::Node::SharedPtr ik_node_; + rclcpp::Executor::SharedPtr ik_executor_; + std::thread ik_thread_; rclcpp::Node::SharedPtr node_; diff --git a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp index 44c86b0691..82f5720e91 100644 --- a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp +++ b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp @@ -124,9 +124,14 @@ bool SrvKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node, const robot_state_ = std::make_shared(robot_model_); robot_state_->setToDefaultValues(); + ik_node_ = std::make_shared("srv_ik_client", node_->get_namespace()); + // Create the ROS2 service client RCLCPP_DEBUG(getLogger(), "IK Service client topic : %s", params_.kinematics_solver_service_name.c_str()); - ik_service_client_ = node_->create_client(params_.kinematics_solver_service_name); + ik_service_client_ = ik_node_->create_client(params_.kinematics_solver_service_name); + ik_executor_ = std::make_unique(); + ik_executor_->add_node(ik_node_); + ik_thread_ = std::thread([this]() { ik_executor_->spin(); }); if (!ik_service_client_->wait_for_service(std::chrono::seconds(1))) { // wait 0.1 seconds, blocking @@ -312,8 +317,8 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vectorget_service_name()); auto result_future = ik_service_client_->async_send_request(ik_srv); - const auto& response = result_future.get(); - if (rclcpp::spin_until_future_complete(node_, result_future) == rclcpp::FutureReturnCode::SUCCESS) + const auto response = result_future.get(); + if (response) { // Check error code error_code.val = response->error_code.val; @@ -352,7 +357,6 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vectorcopyJointGroupPositions(joint_model_group_, solution); @@ -382,7 +386,7 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vector