diff --git a/include/grasp_util.h b/include/grasp_util.h index a6545b0a31a89e72ec0ac13dac459d760221e42a..8953a48c703085c5d9ea45eba269487a3b7bccb5 100644 --- a/include/grasp_util.h +++ b/include/grasp_util.h @@ -76,7 +76,7 @@ public: */ bool pickFromAbove(moveit::planning_interface::MoveGroupInterface &move_group, geometry_msgs::Pose &pick_pose, geometry_msgs::Vector3 dimensions, double open_amount, std::string supporting_surface_id, - std::string object_to_pick_id); + std::string object_to_pick_id, bool plan_only = false); /** * Util method to place an object from above. @@ -88,7 +88,7 @@ public: * @param object_to_place_id ID of the object to place */ bool placeFromAbove(moveit::planning_interface::MoveGroupInterface &move_group, geometry_msgs::Pose &place_pose, - double open_amount, std::string supporting_surface_id, std::string object_to_place_id); + double open_amount, std::string supporting_surface_id, std::string object_to_place_id, bool plan_only = false); }; diff --git a/src/grasping/grasp_service.cpp b/src/grasping/grasp_service.cpp index 5da6b4a8c711ba5941b3877b897ed4ccf8b621a4..7e27a2a4de28d4004599d4bd1a48a57efdc080fe 100644 --- a/src/grasping/grasp_service.cpp +++ b/src/grasping/grasp_service.cpp @@ -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; } diff --git a/src/grasping/grasp_util.cpp b/src/grasping/grasp_util.cpp index 64f79e29e3df4befb46ec8c513ade03e6b08fb31..e8d90c28627ad6140f7255b79374ebeafc7d1585 100644 --- a/src/grasping/grasp_util.cpp +++ b/src/grasping/grasp_util.cpp @@ -75,7 +75,7 @@ GraspUtil::getPickFromAbovePose(geometry_msgs::Pose &object_pose_msg, geometry_m bool GraspUtil::pickFromAbove(moveit::planning_interface::MoveGroupInterface &move_group, geometry_msgs::Pose &pick_pose, geometry_msgs::Vector3 dimensions, - double open_amount, std::string supporting_surface_id, std::string object_to_pick_id) { + double open_amount, std::string supporting_surface_id, std::string object_to_pick_id, bool plan_only) { std::vector<moveit_msgs::Grasp> grasps; grasps.resize(1); @@ -112,7 +112,8 @@ GraspUtil::pickFromAbove(moveit::planning_interface::MoveGroupInterface &move_gr } move_group.setSupportSurfaceName(supporting_surface_id); - moveit_msgs::MoveItErrorCodes 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; @@ -124,7 +125,7 @@ GraspUtil::pickFromAbove(moveit::planning_interface::MoveGroupInterface &move_gr bool GraspUtil::placeFromAbove(moveit::planning_interface::MoveGroupInterface &move_group, geometry_msgs::Pose &place_pose, - double open_amount, std::string supporting_surface_id, std::string object_to_place_id) { + double open_amount, std::string supporting_surface_id, std::string object_to_place_id, bool plan_only) { std::vector<moveit_msgs::PlaceLocation> place_location; place_location.resize(1); @@ -147,7 +148,8 @@ 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 = 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; diff --git a/srv/PickObject.srv b/srv/PickObject.srv index d0e99d06dd54c95cdc72baee1dd97105fe449242..a7f8eb4ec899df0ded89677aec37db7d5c5c7ee0 100644 --- a/srv/PickObject.srv +++ b/srv/PickObject.srv @@ -1,4 +1,5 @@ geometry_msgs/Pose pose geometry_msgs/Vector3 dimensions +bool plan_only --- bool success \ No newline at end of file diff --git a/srv/PlaceObject.srv b/srv/PlaceObject.srv index d0e99d06dd54c95cdc72baee1dd97105fe449242..a7f8eb4ec899df0ded89677aec37db7d5c5c7ee0 100644 --- a/srv/PlaceObject.srv +++ b/srv/PlaceObject.srv @@ -1,4 +1,5 @@ geometry_msgs/Pose pose geometry_msgs/Vector3 dimensions +bool plan_only --- bool success \ No newline at end of file