31 from moveit_msgs.msg
import MoveItErrorCodes
32 from moveit_msgs.msg
import PickupAction, PickupGoal, PlaceAction, PlaceGoal
50 rospy.loginfo(
"Connecting to pickup action...")
55 rospy.loginfo(
"...connected")
56 rospy.loginfo(
"Connecting to place action...")
61 rospy.loginfo(
"...connected")
77 def pickup(self, name, grasps, wait=True, **kwargs):
79 supported_args = (
"allow_gripper_support_collision",
80 "attached_object_touch_links",
81 "allowed_touch_objects",
84 "planning_scene_diff",
87 for arg
in kwargs.keys():
88 if not arg
in supported_args:
89 rospy.loginfo(
"pickup: unsupported argument: %s", arg)
104 g.possible_grasps = grasps
108 g.support_surface_name = kwargs[
"support_name"]
110 g.support_surface_name =
"" 114 g.allow_gripper_support_collision = kwargs[
"allow_gripper_support_collision"]
116 g.allow_gripper_support_collision =
True 120 g.attached_object_touch_links = kwargs[
"attached_object_touch_links"]
122 g.attached_object_touch_links = list()
130 g.planner_id = kwargs[
"planner_id"]
137 g.allowed_touch_objects = kwargs[
"allowed_touch_objects"]
139 g.allowed_touch_objects = list()
143 g.allowed_planning_time = kwargs[
"planning_time"]
149 g.planning_options.planning_scene_diff = kwargs[
"planning_scene_diff"]
151 g.planning_options.planning_scene_diff.is_diff =
True 152 g.planning_options.planning_scene_diff.robot_state.is_diff =
True 153 g.planning_options.plan_only = self.
_plan_only 169 def place(self, name, locations, wait=True, **kwargs):
171 supported_args = (
"allow_gripper_support_collision",
172 "allowed_touch_objects",
176 "planning_scene_diff",
179 for arg
in kwargs.keys():
180 if not arg
in supported_args:
181 rospy.loginfo(
"place: unsupported argument: %s", arg)
187 g.group_name = self.
_group 190 g.attached_object_name = name
193 g.place_locations = locations
197 g.place_eef = kwargs[
"goal_is_eef"]
203 g.support_surface_name = kwargs[
"support_name"]
205 g.support_surface_name =
"" 209 g.allow_gripper_support_collision = kwargs[
"allow_gripper_support_collision"]
211 g.allow_gripper_support_collision =
True 217 g.planner_id = kwargs[
"planner_id"]
224 g.allowed_touch_objects = kwargs[
"allowed_touch_objects"]
226 g.allowed_touch_objects = list()
230 g.allowed_planning_time = kwargs[
"planning_time"]
236 g.planning_options.planning_scene_diff = kwargs[
"planning_scene_diff"]
238 g.planning_options.planning_scene_diff.is_diff =
True 239 g.planning_options.planning_scene_diff.robot_state.is_diff =
True 240 g.planning_options.plan_only = self.
_plan_only 253 rospy.loginfo(
"Beginning to pick.")
256 pick_result = self.
pickup(name, grasps, **kwargs)
257 if pick_result.error_code.val == MoveItErrorCodes.SUCCESS:
258 rospy.loginfo(
"Pick succeeded")
259 return [
True, pick_result]
260 elif pick_result.error_code.val == MoveItErrorCodes.PLANNING_FAILED:
261 rospy.logerr(
"Pick failed in the planning stage, try again...")
264 elif not scene
is None and \
265 (pick_result.error_code.val == MoveItErrorCodes.CONTROL_FAILED
or \
266 pick_result.error_code.val == MoveItErrorCodes.MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE
or \
267 pick_result.error_code.val == MoveItErrorCodes.TIMED_OUT):
268 rospy.logerr(
"Pick failed during execution, attempting to cleanup.")
269 if name
in scene.getKnownAttachedObjects():
270 rospy.loginfo(
"Pick managed to grab object, retreat must have failed, continuing anyways")
271 return [
True, pick_result]
273 rospy.loginfo(
"Pick did not grab object, try again...")
276 rospy.logerr(
"Pick failed with error code: %d. Will retry...",
277 pick_result.error_code.val)
279 rospy.logerr(
"Pick failed, and all retries are used")
280 return [
False, pick_result]
291 rospy.loginfo(
"Beginning to place.")
294 place_result = self.
place(name, locations, **kwargs)
295 if place_result.error_code.val == MoveItErrorCodes.SUCCESS:
296 rospy.loginfo(
"Place succeeded")
297 return [
True, place_result]
298 elif place_result.error_code.val == MoveItErrorCodes.PLANNING_FAILED:
299 rospy.logerr(
"Place failed in planning stage, try again...")
302 elif not scene
is None and \
303 (place_result.error_code.val == MoveItErrorCodes.CONTROL_FAILED
or \
304 place_result.error_code.val == MoveItErrorCodes.MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE
or \
305 place_result.error_code.val == MoveItErrorCodes.TIMED_OUT):
306 rospy.logerr(
"Place failed during execution, attempting to cleanup.")
307 if name
in scene.getKnownAttachedObjects():
308 rospy.loginfo(
"Place did not place object, approach must have failed, will retry...")
311 rospy.loginfo(
"Object no longer in gripper, must be placed, continuing...")
312 return [
True, place_result]
314 rospy.logerr(
"Place failed with error code: %d. Will retry...",
315 place_result.error_code.val)
317 rospy.logerr(
"Place failed, and all retries are used")
318 return [
False, place_result]
def pickup(self, name, grasps, wait=True, kwargs)
Plan and grasp something.
def place_with_retry(self, name, locations, retries=5, scene=None, kwargs)
Common usage pattern TODO document.
def pick_with_retry(self, name, grasps, retries=5, scene=None, kwargs)
Common usage pattern TODO document.
def get_place_action(self)
def place(self, name, locations, wait=True, kwargs)
Plan and grasp something.
def get_pick_action(self)
def __init__(self, group="arm", ee_group="gripper", plan_only=False, verbose=False)
Create a grasp manager, connect actions.
Simple interface to pick and place actions.