Skip to content
Snippets Groups Projects
Commit 9326ad1c authored by Sebastian Ebert's avatar Sebastian Ebert
Browse files

fixes from merge request

parent 6e66b3b9
No related branches found
No related tags found
No related merge requests found
......@@ -74,7 +74,7 @@ bool pickObject(panda_grasping::PickObject::Request &req,
ROS_INFO("Picking up ...");
// 0.08 = 8cm = maximum gripper opening
if (!grasp_util.pickFromAbove(group, pick_pose, req.dimensions, 0.08, "pick_support", "pick_object")) {
if (!grasp_util.pickFromAbove(group, pick_pose, req.dimensions, 0.08, "pick_support", "pick_object", req.plan_only)) {
res.success = false;
return false;
}
......@@ -121,7 +121,7 @@ placeObject(panda_grasping::PlaceObject::Request &req, panda_grasping::PlaceObje
}
ROS_INFO("Placing object.");
if (!grasp_util.placeFromAbove(group, req.pose, 0.08, "place_support", "pick_object")) {
if (!grasp_util.placeFromAbove(group, req.pose, 0.08, "place_support", "pick_object", req.plan_only)) {
res.success = false;
return false;
}
......
......@@ -113,13 +113,7 @@ GraspUtil::pickFromAbove(moveit::planning_interface::MoveGroupInterface &move_gr
move_group.setSupportSurfaceName(supporting_surface_id);
moveit_msgs::MoveItErrorCodes miec;
if(plan_only){
miec = move_group.pick(object_to_pick_id, grasps, true);
}else{
miec = move_group.pick(object_to_pick_id, grasps);
}
moveit_msgs::MoveItErrorCodes miec = move_group.pick(object_to_pick_id, grasps, plan_only);
if (miec.val == miec.SUCCESS) {
return true;
......@@ -155,13 +149,7 @@ GraspUtil::placeFromAbove(moveit::planning_interface::MoveGroupInterface &move_g
setupOpenGripper(place_location[0].post_place_posture, open_amount);
move_group.setSupportSurfaceName(supporting_surface_id);
moveit_msgs::MoveItErrorCodes miec;
if(plan_only){
miec = move_group.place(object_to_place_id, place_location, true);
}else{
miec = move_group.place(object_to_place_id, place_location);
}
moveit_msgs::MoveItErrorCodes miec = move_group.place(object_to_place_id, place_location, plan_only);
if (miec.val == miec.SUCCESS) {
return true;
......
geometry_msgs/Pose pose
geometry_msgs/Vector3 dimensions
bool plan_only
---
bool success
\ No newline at end of file
geometry_msgs/Pose pose
geometry_msgs/Vector3 dimensions
bool plan_only
---
bool success
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment