diff --git a/capabilities/src/execute_task_solution_capability.cpp b/capabilities/src/execute_task_solution_capability.cpp index 7003c144c..7e53d4362 100644 --- a/capabilities/src/execute_task_solution_capability.cpp +++ b/capabilities/src/execute_task_solution_capability.cpp @@ -87,6 +87,8 @@ namespace move_group { ExecuteTaskSolutionCapability::ExecuteTaskSolutionCapability() : MoveGroupCapability("ExecuteTaskSolution") {} void ExecuteTaskSolutionCapability::initialize() { + action_callback_group_ = + context_->moveit_cpp_->getNode()->create_callback_group(rclcpp::CallbackGroupType::Reentrant); // configure the action server as_ = rclcpp_action::create_server( context_->moveit_cpp_->getNode(), "execute_task_solution", @@ -95,7 +97,8 @@ void ExecuteTaskSolutionCapability::initialize() { ActionServerType::CancelCallback( std::bind(&ExecuteTaskSolutionCapability::preemptCallback, this, std::placeholders::_1)), ActionServerType::AcceptedCallback( - std::bind(&ExecuteTaskSolutionCapability::goalCallback, this, std::placeholders::_1))); + std::bind(&ExecuteTaskSolutionCapability::goalCallback, this, std::placeholders::_1)), + rcl_action_server_get_default_options(), action_callback_group_); } void ExecuteTaskSolutionCapability::goalCallback( diff --git a/capabilities/src/execute_task_solution_capability.h b/capabilities/src/execute_task_solution_capability.h index 366347da7..53cf6c499 100644 --- a/capabilities/src/execute_task_solution_capability.h +++ b/capabilities/src/execute_task_solution_capability.h @@ -75,6 +75,7 @@ class ExecuteTaskSolutionCapability : public MoveGroupCapability } ActionServerType::SharedPtr as_; + rclcpp::CallbackGroup::SharedPtr action_callback_group_; }; } // namespace move_group diff --git a/core/src/task.cpp b/core/src/task.cpp index 9d1694fce..009d609c2 100644 --- a/core/src/task.cpp +++ b/core/src/task.cpp @@ -301,9 +301,17 @@ moveit_msgs::msg::MoveItErrorCodes Task::execute(const SolutionBase& s) { } auto result_future = ac->async_get_result(goal_handle); - if (rclcpp::spin_until_future_complete(node, result_future) != rclcpp::FutureReturnCode::SUCCESS) { - RCLCPP_ERROR(node->get_logger(), "Get result call failed"); - return error_code; + while (result_future.wait_for(std::chrono::milliseconds(10)) != std::future_status::ready) { + if (pimpl()->preempt_requested_) { + auto cancel_future = ac->async_cancel_goal(goal_handle); + if (rclcpp::spin_until_future_complete(node, cancel_future) != rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_ERROR(node->get_logger(), "Could not preempt execution"); + return error_code; + } else { + error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED; + return error_code; + } + } } auto result = result_future.get();