Pure python interface to move_group action.
More...
|
def | __init__ (self, group, frame, listener=None, plan_only=False) |
| Constructor for this utility. More...
|
|
def | get_move_action (self) |
|
def | moveToJointPosition (self, joints, positions, tolerance=0.01, wait=True, kwargs) |
| Move the arm to set of joint position goals. More...
|
|
def | moveToPose (self, pose_stamped, gripper_frame, tolerance=0.01, wait=True, kwargs) |
| Move the arm, based on a goal pose_stamped for the end effector. More...
|
|
def | setPlannerId (self, planner_id) |
| Sets the planner_id used for all future planning requests. More...
|
|
def | setPlanningTime (self, time) |
| Set default planning time to be used for future planning request. More...
|
|
Pure python interface to move_group action.
Definition at line 38 of file move_group_interface.py.
def moveit_python.move_group_interface.MoveGroupInterface.__init__ |
( |
|
self, |
|
|
|
group, |
|
|
|
frame, |
|
|
|
listener = None , |
|
|
|
plan_only = False |
|
) |
| |
Constructor for this utility.
- Parameters
-
group | Name of the MoveIt! group to command |
frame | Name of the fixed frame in which planning happens |
listener | A TF listener instance (optional, will create a new one if None) |
plan_only | Should we only plan, but not execute? |
Definition at line 45 of file move_group_interface.py.
def moveit_python.move_group_interface.MoveGroupInterface.get_move_action |
( |
|
self | ) |
|
def moveit_python.move_group_interface.MoveGroupInterface.moveToJointPosition |
( |
|
self, |
|
|
|
joints, |
|
|
|
positions, |
|
|
|
tolerance = 0.01 , |
|
|
|
wait = True , |
|
|
|
kwargs |
|
) |
| |
def moveit_python.move_group_interface.MoveGroupInterface.moveToPose |
( |
|
self, |
|
|
|
pose_stamped, |
|
|
|
gripper_frame, |
|
|
|
tolerance = 0.01 , |
|
|
|
wait = True , |
|
|
|
kwargs |
|
) |
| |
def moveit_python.move_group_interface.MoveGroupInterface.setPlannerId |
( |
|
self, |
|
|
|
planner_id |
|
) |
| |
Sets the planner_id used for all future planning requests.
- Parameters
-
planner_id | The string for the planner id, set to None to clear |
Definition at line 272 of file move_group_interface.py.
def moveit_python.move_group_interface.MoveGroupInterface.setPlanningTime |
( |
|
self, |
|
|
|
time |
|
) |
| |
moveit_python.move_group_interface.MoveGroupInterface._action |
|
private |
moveit_python.move_group_interface.MoveGroupInterface._fixed_frame |
|
private |
moveit_python.move_group_interface.MoveGroupInterface._group |
|
private |
moveit_python.move_group_interface.MoveGroupInterface._listener |
|
private |
moveit_python.move_group_interface.MoveGroupInterface.plan_only |
moveit_python.move_group_interface.MoveGroupInterface.planner_id |
moveit_python.move_group_interface.MoveGroupInterface.planning_time |
The documentation for this class was generated from the following file: