Skip to content

Commit

Permalink
Added GILRelease to pick and place (moveit#2272)
Browse files Browse the repository at this point in the history
  • Loading branch information
gerardcanal committed Aug 21, 2020
1 parent e7c99e4 commit 35a53f5
Showing 1 changed file with 7 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -270,6 +270,7 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
convertListToPose(pose, msg.pose);
msg.header.frame_id = getPoseReferenceFrame();
msg.header.stamp = ros::Time::now();
GILReleaser gr;
return place(object_name, msg, plan_only) == MoveItErrorCode::SUCCESS;
}

Expand All @@ -279,6 +280,7 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
std::vector<geometry_msgs::PoseStamped> poses(l);
for (int i = 0; i < l; ++i)
py_bindings_tools::deserializeMsg(py_bindings_tools::ByteString(poses_list[i]), poses[i]);
GILReleaser gr;
return place(object_name, poses, plan_only) == MoveItErrorCode::SUCCESS;
}

Expand All @@ -287,6 +289,7 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
{
std::vector<moveit_msgs::PlaceLocation> locations(1);
py_bindings_tools::deserializeMsg(location_str, locations[0]);
GILReleaser gr;
return place(object_name, std::move(locations), plan_only) == MoveItErrorCode::SUCCESS;
}

Expand All @@ -296,11 +299,13 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
std::vector<moveit_msgs::PlaceLocation> locations(l);
for (int i = 0; i < l; ++i)
py_bindings_tools::deserializeMsg(py_bindings_tools::ByteString(location_list[i]), locations[i]);
GILReleaser gr;
return place(object_name, std::move(locations), plan_only) == MoveItErrorCode::SUCCESS;
}

bool placeAnywhere(const std::string& object_name, bool plan_only = false)
{
GILReleaser gr;
return place(object_name, plan_only) == MoveItErrorCode::SUCCESS;
}

Expand Down Expand Up @@ -501,6 +506,7 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
{
moveit_msgs::Grasp grasp;
py_bindings_tools::deserializeMsg(grasp_str, grasp);
GILReleaser gr;
return pick(object, grasp, plan_only).val;
}

Expand All @@ -510,6 +516,7 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
std::vector<moveit_msgs::Grasp> grasps(l);
for (int i = 0; i < l; ++i)
py_bindings_tools::deserializeMsg(py_bindings_tools::ByteString(grasp_list[i]), grasps[i]);
GILReleaser gr;
return pick(object, std::move(grasps), plan_only).val;
}

Expand Down

0 comments on commit 35a53f5

Please sign in to comment.