Skip to content

Commit

Permalink
Handle asynchronous feedback
Browse files Browse the repository at this point in the history
The grasp detection flag is an atomic bool. The scope of the
grasp candidate's mutex has been moved.
  • Loading branch information
bostoncleek committed Jun 17, 2022
1 parent e671e06 commit 5145e0c
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 5 deletions.
6 changes: 3 additions & 3 deletions core/include/moveit/task_constructor/stages/grasp_provider.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,9 +98,9 @@ class GraspProvider : public GeneratePose, ActionBase
void onNewSolution(const SolutionBase& s) override;

private:
std::mutex grasp_mutex_;
bool found_candidates_;
std::vector<moveit_msgs::Grasp> grasp_candidates_;
std::mutex grasp_mutex_; // Protects grasp candidates
std::atomic_bool found_candidates_; // Flag indicates the discovery of grasps
std::vector<moveit_msgs::Grasp> grasp_candidates_; // Grasp Candidates
};
} // namespace stages
} // namespace task_constructor
Expand Down
7 changes: 5 additions & 2 deletions core/src/stages/grasp_provider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,11 @@ void GraspProvider::activeCallback() {
}

void GraspProvider::feedbackCallback(const grasping_msgs::GraspPlanningFeedbackConstPtr& feedback) {
found_candidates_ = true;

// Protect grasp candidate incase feedback is sent asynchronously
const std::lock_guard<std::mutex> lock(grasp_mutex_);
grasp_candidates_ = feedback->grasps;
found_candidates_ = true;
}

void GraspProvider::doneCallback(const actionlib::SimpleClientGoalState& state,
Expand Down Expand Up @@ -158,8 +160,9 @@ void GraspProvider::compute() {

// monitor feedback/results
// blocking function untill timeout reached or results received
const std::lock_guard<std::mutex> lock(grasp_mutex_);
if (monitorGoal()) {
// Protect grasp candidate incase feedback is being recieved asynchronously
const std::lock_guard<std::mutex> lock(grasp_mutex_);
for (unsigned int i = 0; i < grasp_candidates_.size(); i++) {
InterfaceState state(scene);
state.properties().set("target_pose", grasp_candidates_.at(i).grasp_pose);
Expand Down

0 comments on commit 5145e0c

Please sign in to comment.