Skip to content

Commit 9cd3fe0

Browse files
committed
Handle asynchronous feedback
The grasp detection flag is an atomic bool. The scope of the grasp candidate's mutex has been moved.
1 parent 34024de commit 9cd3fe0

File tree

2 files changed

+9
-5
lines changed

2 files changed

+9
-5
lines changed

core/include/moveit/task_constructor/stages/grasp_provider.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -98,9 +98,9 @@ class GraspProvider : public GeneratePose, ActionBase
9898
void onNewSolution(const SolutionBase& s) override;
9999

100100
private:
101-
std::mutex grasp_mutex_;
102-
bool found_candidates_;
103-
std::vector<moveit_msgs::Grasp> grasp_candidates_;
101+
std::mutex grasp_mutex_; // Protects grasp candidates
102+
std::atomic_bool found_candidates_; // Flag indicates the discovery of grasps
103+
std::vector<moveit_msgs::Grasp> grasp_candidates_; // Grasp Candidates
104104
};
105105
} // namespace stages
106106
} // namespace task_constructor

core/src/stages/grasp_provider.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -94,9 +94,11 @@ void GraspProvider::activeCallback() {
9494
}
9595

9696
void GraspProvider::feedbackCallback(const grasping_msgs::GraspPlanningFeedbackConstPtr& feedback) {
97+
found_candidates_ = true;
98+
99+
// Protect grasp candidate incase feedback is sent asynchronously
97100
const std::lock_guard<std::mutex> lock(grasp_mutex_);
98101
grasp_candidates_ = feedback->grasps;
99-
found_candidates_ = true;
100102
}
101103

102104
void GraspProvider::doneCallback(const actionlib::SimpleClientGoalState& state,
@@ -158,8 +160,10 @@ void GraspProvider::compute() {
158160

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

0 commit comments

Comments
 (0)