Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Run goalcallback asynchronously #496

Merged
merged 5 commits into from
Oct 27, 2023
Merged
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
22 changes: 16 additions & 6 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,12 +90,22 @@ void ExecuteTaskSolutionCapability::initialize() {
// configure the action server
as_ = rclcpp_action::create_server<moveit_task_constructor_msgs::action::ExecuteTaskSolution>(
context_->moveit_cpp_->getNode(), "execute_task_solution",
ActionServerType::GoalCallback(std::bind(&ExecuteTaskSolutionCapability::handleNewGoal, this,
std::placeholders::_1, std::placeholders::_2)),
ActionServerType::CancelCallback(
std::bind(&ExecuteTaskSolutionCapability::preemptCallback, this, std::placeholders::_1)),
ActionServerType::AcceptedCallback(
std::bind(&ExecuteTaskSolutionCapability::goalCallback, this, std::placeholders::_1)));
[this](const rclcpp_action::GoalUUID& /*uuid*/,
const ExecuteTaskSolutionAction::Goal::ConstSharedPtr& /*goal*/) {
// Reject new goal if another goal is currently processed
if (last_goal_future_.valid() &&
sjahr marked this conversation as resolved.
Show resolved Hide resolved
last_goal_future_.wait_for(std::chrono::seconds::zero()) != std::future_status::ready) {
return rclcpp_action::GoalResponse::REJECT;
}
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle) {
return preemptCallback(goal_handle);
},
[this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle) {
last_goal_future_ =
std::async(std::launch::async, &ExecuteTaskSolutionCapability::goalCallback, this, goal_handle);
});
}

void ExecuteTaskSolutionCapability::goalCallback(
Expand Down
7 changes: 1 addition & 6 deletions capabilities/src/execute_task_solution_capability.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,13 +68,8 @@ class ExecuteTaskSolutionCapability : public MoveGroupCapability
rclcpp_action::CancelResponse
preemptCallback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle);

/** Always accept the goal */
rclcpp_action::GoalResponse handleNewGoal(const rclcpp_action::GoalUUID& /*uuid*/,
const ExecuteTaskSolutionAction::Goal::ConstSharedPtr& /*goal*/) const {
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}

ActionServerType::SharedPtr as_;
std::future<void> last_goal_future_;
};

} // namespace move_group
Loading