Simple interface to pick and place actions. More...
Public Member Functions | |
def | __init__ |
Create a grasp manager, connect actions. | |
def | get_pick_action |
def | get_place_action |
def | pick_with_retry |
Common usage pattern TODO document. | |
def | pickup |
Plan and grasp something. | |
def | place |
Plan and grasp something. | |
def | place_with_retry |
Common usage pattern TODO document. | |
Public Attributes | |
allowed_planning_time | |
planner_id | |
Private Attributes | |
_effector | |
_group | |
_pick_action | |
_place_action | |
_plan_only | |
_verbose |
Simple interface to pick and place actions.
Definition at line 35 of file pick_place_interface.py.
def moveit_python.pick_place_interface.PickPlaceInterface.__init__ | ( | self, | |
group = "arm" , |
|||
ee_group = "gripper" , |
|||
plan_only = False , |
|||
verbose = False |
|||
) |
Create a grasp manager, connect actions.
group | Name of arm planning group |
ee_group | Name of end effector planning group |
plan_only | Should we only plan, but not execute? |
Definition at line 41 of file pick_place_interface.py.
Definition at line 66 of file pick_place_interface.py.
Definition at line 69 of file pick_place_interface.py.
def moveit_python.pick_place_interface.PickPlaceInterface.pick_with_retry | ( | self, | |
name, | |||
grasps, | |||
retries = 5 , |
|||
scene = None , |
|||
kwargs | |||
) |
Common usage pattern TODO document.
Definition at line 250 of file pick_place_interface.py.
def moveit_python.pick_place_interface.PickPlaceInterface.pickup | ( | self, | |
name, | |||
grasps, | |||
wait = True , |
|||
kwargs | |||
) |
Plan and grasp something.
name | Name of the object to grasp |
grasps | Grasps to try (moveit_msgs/Grasp) |
support_name | Name of the support surface |
Definition at line 77 of file pick_place_interface.py.
def moveit_python.pick_place_interface.PickPlaceInterface.place | ( | self, | |
name, | |||
locations, | |||
wait = True , |
|||
kwargs | |||
) |
Plan and grasp something.
name | Name of the object to grasp |
grasps | Grasps to try (moveit_msgs/Grasp) |
support_name | Name of the support surface |
goal_is_eef | Set to true if the place goal is for the end effector frame, default is object frame. |
Definition at line 168 of file pick_place_interface.py.
def moveit_python.pick_place_interface.PickPlaceInterface.place_with_retry | ( | self, | |
name, | |||
locations, | |||
retries = 5 , |
|||
scene = None , |
|||
kwargs | |||
) |
Common usage pattern TODO document.
Definition at line 283 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.
Definition at line 41 of file pick_place_interface.py.