Public Member Functions | Private Attributes
moveit_commander.move_group.MoveGroupCommander Class Reference

List of all members.

Public Member Functions

def __init__
def allow_looking
def allow_replanning
def attach_object
def clear_path_constraints
def clear_pose_target
def clear_pose_targets
def compute_cartesian_path
def detach_object
def execute
def forget_joint_values
def get_active_joints
def get_current_joint_values
def get_current_pose
def get_current_rpy
def get_end_effector_link
def get_goal_joint_tolerance
def get_goal_orientation_tolerance
def get_goal_position_tolerance
def get_goal_tolerance
def get_joints
def get_known_constraints
def get_name
def get_path_constraints
def get_planning_frame
def get_planning_time
def get_pose_reference_frame
def get_random_joint_values
def get_random_pose
def get_remembered_joint_values
def get_variable_count
def go
def has_end_effector_link
def pick
def place
def plan
def remember_joint_values
def set_constraints_database
def set_end_effector_link
def set_goal_joint_tolerance
def set_goal_orientation_tolerance
def set_goal_position_tolerance
def set_goal_tolerance
def set_joint_value_target
def set_named_target
def set_orientation_target
def set_path_constraints
def set_planner_id
def set_planning_time
def set_pose_reference_frame
def set_pose_target
def set_pose_targets
def set_position_target
def set_random_target
def set_rpy_target
def set_start_state
def set_start_state_to_current_state
def set_support_surface_name
def set_workspace
def shift_pose_target
def stop

Private Attributes

 _g

Detailed Description

Execution of simple commands for a particular group

Definition at line 44 of file move_group.py.


Constructor & Destructor Documentation

Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error. 

Definition at line 49 of file move_group.py.


Member Function Documentation

Enable/disable looking around for motion planning 

Definition at line 330 of file move_group.py.

Enable/disable replanning 

Definition at line 334 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.attach_object (   self,
  object_name,
  link_name = "",
  touch_links = [] 
)
Given the name of an object existing in the planning scene, attach it to a link. The link used is specified by the second argument. If left unspecified, the end-effector link is used, if one is known. If there is no end-effector link, the first link in the group is used. If no link is identified, failure is reported. True is returned if an attach request was succesfully sent to the move_group node. This does not verify that the attach request also was successfuly applied by move_group.

Definition at line 442 of file move_group.py.

Specify that no path constraints are to be used during motion planning 

Definition at line 359 of file move_group.py.

Clear the pose target for a particular end-effector 

Definition at line 267 of file move_group.py.

Clear all known pose targets 

Definition at line 271 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.compute_cartesian_path (   self,
  waypoints,
  eef_step,
  jump_threshold,
  avoid_collisions = True 
)
Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the poses specified as waypoints. Configurations are computed for every eef_step meters; The jump_threshold specifies the maximum distance in configuration space between consecutive points in the resultingpath. The return value is a tuple: a fraction of how much of the path was followed, the actual RobotTrajectory. 

Definition at line 431 of file move_group.py.

Given the name of a link, detach the object(s) from that link. If no such link exists, the name is interpreted as an object name. If there is no name specified, an attempt is made to detach all objects attached to any link in the group.

Definition at line 446 of file move_group.py.

Execute a previously planned path

Definition at line 438 of file move_group.py.

Forget a stored joint configuration 

Definition at line 294 of file move_group.py.

Get the active joints of this group 

Definition at line 61 of file move_group.py.

Get the current configuration of the group as a list (these are values published on /joint_states) 

Definition at line 98 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.get_current_pose (   self,
  end_effector_link = "" 
)
Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector. 

Definition at line 102 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.get_current_rpy (   self,
  end_effector_link = "" 
)
Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector. 

Definition at line 109 of file move_group.py.

Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector. 

Definition at line 77 of file move_group.py.

Get the tolerance for achieving a joint goal (distance for each joint variable) 

Definition at line 302 of file move_group.py.

When moving to an orientation goal or to a pose goal, the tolerance for the goal orientation is specified as the distance (roll, pitch, yaw) to the target origin of the end-effector 

Definition at line 310 of file move_group.py.

When moving to a position goal or to a pose goal, the tolerance for the goal position is specified as the radius a sphere around the target origin of the end-effector 

Definition at line 306 of file move_group.py.

Return a tuple of goal tolerances: joint, position and orientation. 

Definition at line 298 of file move_group.py.

Get the joints of this group 

Definition at line 65 of file move_group.py.

Get a list of names for the constraints specific for this group, as read from the warehouse 

Definition at line 338 of file move_group.py.

Get the name of the group this instance was initialized for 

Definition at line 53 of file move_group.py.

Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints 

Definition at line 342 of file move_group.py.

Get the name of the frame where all planning is performed 

Definition at line 94 of file move_group.py.

Specify the amount of time to be used for motion planning. 

Definition at line 371 of file move_group.py.

Get the reference frame assumed for poses of end-effectors 

Definition at line 86 of file move_group.py.

Definition at line 116 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.get_random_pose (   self,
  end_effector_link = "" 
)

Definition at line 119 of file move_group.py.

Get a dictionary that maps names to joint configurations for the group 

Definition at line 290 of file move_group.py.

Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)

Definition at line 69 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.go (   self,
  joints = None,
  wait = True 
)
Set the target of the group and then move the group to the specified target 

Definition at line 392 of file move_group.py.

Check if this group has a link that is considered to be an end effector 

Definition at line 73 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.pick (   self,
  object_name,
  grasp = [] 
)
Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument.

Definition at line 450 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.place (   self,
  object_name,
  location = None 
)
Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided

Definition at line 457 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.plan (   self,
  joints = None 
)
Return a motion plan (a RobotTrajectory) to the set goal state (or specified by the joints argument) 

Definition at line 414 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.remember_joint_values (   self,
  name,
  values = None 
)
Record the specified joint configuration of the group under the specified name. If no values are specified, the current state of the group is recorded. 

Definition at line 284 of file move_group.py.

Specify which database to connect to for loading possible path constraints 

Definition at line 363 of file move_group.py.

Set the name of the link to be considered as an end effector 

Definition at line 81 of file move_group.py.

Set the tolerance for a target joint configuration 

Definition at line 318 of file move_group.py.

Set the tolerance for a target end-effector orientation 

Definition at line 326 of file move_group.py.

Set the tolerance for a target end-effector position 

Definition at line 322 of file move_group.py.

Set the joint, position and orientation goal tolerances simultaneously 

Definition at line 314 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.set_joint_value_target (   self,
  arg1,
  arg2 = None,
  arg3 = None 
)
Specify a target joint configuration for the group.
- if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided.
The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values
for the group. The JointState message specifies the positions of some single-dof joints. 
- if the type of arg1 is string, then arg2 is expected to be defined and be either a real value or a list of real values. This is
interpreted as setting a particular joint to a particular value.
- if the type of arg1 is Pose or PoseStamped, both arg2 and arg3 could be defined. If arg2 or arg3 are defined, their types must
be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use
the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation
allows setting the joint target of the group by calling IK. This does not send a pose to the planner and the planner will do no IK.
Instead, one IK solution will be computed first, and that will be sent to the planner. 

Definition at line 131 of file move_group.py.

Set a joint configuration by name. The name can be a name previlusy remembered with remember_joint_values() or a configuration specified in the SRDF. 

Definition at line 279 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.set_orientation_target (   self,
  q,
  end_effector_link = "" 
)
Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.

Definition at line 204 of file move_group.py.

Specify the path constraints to be used (as read from the database) 

Definition at line 349 of file move_group.py.

Specify which planner to use when motion planning 

Definition at line 375 of file move_group.py.

Specify the amount of time to be used for motion planning. 

Definition at line 367 of file move_group.py.

Set the reference frame to assume for poses of end-effectors 

Definition at line 90 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.set_pose_target (   self,
  pose,
  end_effector_link = "" 
)
Set the pose of the end-effector, if one is available. The expected input is a Pose message, a PoseStamped message or a list of 6 floats:
[x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] 

Definition at line 223 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.set_pose_targets (   self,
  poses,
  end_effector_link = "" 
)
Set the pose of the end-effector, if one is available. The expected input is a list of poses. Each pose can be a Pose message, a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] 

Definition at line 242 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.set_position_target (   self,
  xyz,
  end_effector_link = "" 
)
Specify a target position for the end-effector. Any orientation of the end-effector is acceptable.

Definition at line 215 of file move_group.py.

Set a random joint configuration target 

Definition at line 275 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.set_rpy_target (   self,
  rpy,
  end_effector_link = "" 
)
Specify a target orientation for the end-effector. Any position of the end-effector is acceptable.

Definition at line 193 of file move_group.py.

Definition at line 128 of file move_group.py.

Definition at line 125 of file move_group.py.

Set the support surface name for a place operation 

Definition at line 475 of file move_group.py.

Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ] 

Definition at line 379 of file move_group.py.

def moveit_commander.move_group.MoveGroupCommander.shift_pose_target (   self,
  axis,
  value,
  end_effector_link = "" 
)
Get the current pose of the end effector, add value to the corresponding axis (0..5: X, Y, Z, R, P, Y) and set the new pose as the pose target 

Definition at line 250 of file move_group.py.

Stop the current execution, if any 

Definition at line 57 of file move_group.py.


Member Data Documentation

Definition at line 49 of file move_group.py.


The documentation for this class was generated from the following file:


moveit_commander
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:38:52