move_group.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Ioan Sucan
00034 
00035 from geometry_msgs.msg import Pose, PoseStamped
00036 from moveit_msgs.msg import RobotTrajectory, Grasp, PlaceLocation, Constraints
00037 from sensor_msgs.msg import JointState
00038 import rospy
00039 import tf
00040 from moveit_ros_planning_interface import _moveit_move_group_interface
00041 from exception import MoveItCommanderException
00042 import conversions
00043 
00044 class MoveGroupCommander(object):
00045     """
00046     Execution of simple commands for a particular group
00047     """
00048 
00049     def __init__(self, name):
00050         """ Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error. """
00051         self._g = _moveit_move_group_interface.MoveGroup(name, "robot_description")
00052 
00053     def get_name(self):
00054         """ Get the name of the group this instance was initialized for """
00055         return self._g.get_name()
00056 
00057     def stop(self):
00058         """ Stop the current execution, if any """
00059         self._g.stop()
00060 
00061     def get_active_joints(self):
00062         """ Get the active joints of this group """
00063         return self._g.get_active_joints()
00064 
00065     def get_joints(self):
00066         """ Get the joints of this group """
00067         return self._g.get_joints()
00068 
00069     def get_variable_count(self):
00070         """ Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)"""
00071         return self._g.get_variable_count()
00072 
00073     def has_end_effector_link(self):
00074         """ Check if this group has a link that is considered to be an end effector """
00075         return len(self._g.get_end_effector_link()) > 0
00076 
00077     def get_end_effector_link(self):
00078         """ Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector. """
00079         return self._g.get_end_effector_link()
00080 
00081     def set_end_effector_link(self, link_name):
00082         """ Set the name of the link to be considered as an end effector """
00083         if not self._g.set_end_effector_link(link_name):
00084             raise MoveItCommanderException("Unable to set end efector link")
00085 
00086     def get_pose_reference_frame(self):
00087         """ Get the reference frame assumed for poses of end-effectors """
00088         return self._g.get_pose_reference_frame()
00089 
00090     def set_pose_reference_frame(self, reference_frame):
00091         """ Set the reference frame to assume for poses of end-effectors """
00092         self._g.set_pose_reference_frame(reference_frame)
00093     
00094     def get_planning_frame(self):
00095         """ Get the name of the frame where all planning is performed """
00096         return self._g.get_planning_frame()
00097 
00098     def get_current_joint_values(self):
00099         """ Get the current configuration of the group as a list (these are values published on /joint_states) """
00100         return self._g.get_current_joint_values()
00101 
00102     def get_current_pose(self, end_effector_link = ""):
00103         """ Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector. """
00104         if len(end_effector_link) > 0 or self.has_end_effector_link():
00105             return conversions.list_to_pose_stamped(self._g.get_current_pose(end_effector_link), self.get_planning_frame())
00106         else:
00107             raise MoveItCommanderException("There is no end effector to get the pose of")
00108 
00109     def get_current_rpy(self, end_effector_link = ""):
00110         """ Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector. """
00111         if len(end_effector_link) > 0 or self.has_end_effector_link():
00112             return self._g.get_current_rpy(end_effector_link)
00113         else:
00114             raise MoveItCommanderException("There is no end effector to get the rpy of")
00115 
00116     def get_random_joint_values(self):
00117         return self._g.get_random_joint_values()
00118 
00119     def get_random_pose(self, end_effector_link = ""):
00120         if len(end_effector_link) > 0 or self.has_end_effector_link():
00121             return conversions.list_to_pose_stamped(self._g.get_random_pose(end_effector_link), self.get_planning_frame())
00122         else:
00123             raise MoveItCommanderException("There is no end effector to get the pose of")
00124 
00125     def set_start_state_to_current_state(self):
00126         self._g.set_start_state_to_current_state()
00127 
00128     def set_start_state(self, msg):
00129         self._g.set_start_state(conversions.msg_to_string(msg))
00130 
00131     def set_joint_value_target(self, arg1, arg2 = None, arg3 = None):
00132         """
00133         Specify a target joint configuration for the group.
00134         - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided.
00135         The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values
00136         for the group. The JointState message specifies the positions of some single-dof joints. 
00137         - 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
00138         interpreted as setting a particular joint to a particular value.
00139         - 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
00140         be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use
00141         the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation
00142         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.
00143         Instead, one IK solution will be computed first, and that will be sent to the planner. 
00144         """
00145         if (type(arg1) is dict) or (type(arg1) is list):
00146             if (arg2 != None or arg3 != None):
00147                 raise MoveItCommanderException("Too many arguments specified")
00148             if not self._g.set_joint_value_target(arg1):
00149                 raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
00150             return
00151         if type(arg1) is JointState:
00152             if (arg2 != None or arg3 != None):
00153                 raise MoveItCommanderException("Too many arguments specified")
00154             if not self._g.set_joint_value_target_from_joint_state_message(conversions.msg_to_string(arg1)):
00155                 raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
00156         if (type(arg1) is str):
00157             if (arg2 == None):
00158                 raise MoveItCommanderException("Joint value expected when joint name specified")
00159             if (arg3 != None):
00160                 raise MoveItCommanderException("Too many arguments specified")
00161             if not self._g.set_joint_value_target(arg1, arg2):
00162                 raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
00163         if (type(arg1) is PoseStamped) or (type(arg1) is Pose):
00164             approx = False
00165             eef = ""
00166             if (arg2 != None):
00167                 if type(arg2) is str:
00168                     eef = arg2
00169                 else:
00170                     if type(arg2) is bool:
00171                         approx = arg2
00172                     else:
00173                         raise MoveItCommanderException("Unexpected type")
00174             if (arg3 != None):
00175                 if type(arg3) is str:
00176                     eef = arg3
00177                 else:
00178                     if type(arg3) is bool:
00179                         approx = arg3
00180                     else:
00181                         raise MoveItCommanderException("Unexpected type")
00182             r = False
00183             if type(arg1) is PoseStamped:
00184                 r = self._g.set_joint_value_target_from_pose_stamped(conversions.msg_to_string(arg1), eef, approx)
00185             else:
00186                 r = self._g.set_joint_value_target_from_pose(conversions.msg_to_string(arg1), eef, approx)
00187             if not r:
00188                 if approx:
00189                     raise MoveItCommanderException("Error setting joint target. Does your IK solver support approximate IK?")
00190                 else:
00191                     raise MoveItCommanderException("Error setting joint target. Is IK running?")
00192 
00193     def set_rpy_target(self, rpy, end_effector_link = ""):
00194         """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
00195         if len(end_effector_link) > 0 or self.has_end_effector_link():
00196             if len(rpy) == 3:
00197                 if not self._g.set_rpy_target(rpy[0], rpy[1], rpy[2], end_effector_link):
00198                     raise MoveItCommanderException("Unable to set orientation target")
00199             else:
00200                 raise MoveItCommanderException("Expected [roll, pitch, yaw]")
00201         else:
00202             raise MoveItCommanderException("There is no end effector to set the pose for")
00203 
00204     def set_orientation_target(self, q, end_effector_link = ""):
00205         """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
00206         if len(end_effector_link) > 0 or self.has_end_effector_link():
00207             if len(q) == 4:
00208                 if not self._g.set_orientation_target(q[0], q[1], q[2], q[3], end_effector_link):
00209                     raise MoveItCommanderException("Unable to set orientation target")
00210             else:
00211                 raise MoveItCommanderException("Expected [qx, qy, qz, qw]")
00212         else:
00213             raise MoveItCommanderException("There is no end effector to set the pose for")
00214 
00215     def set_position_target(self, xyz, end_effector_link = ""):
00216         """ Specify a target position for the end-effector. Any orientation of the end-effector is acceptable."""
00217         if len(end_effector_link) > 0 or self.has_end_effector_link():
00218             if not self._g.set_position_target(xyz[0], xyz[1], xyz[2], end_effector_link):
00219                 raise MoveItCommanderException("Unable to set position target")
00220         else:
00221             raise MoveItCommanderException("There is no end effector to set the pose for")
00222 
00223     def set_pose_target(self, pose, end_effector_link = ""):
00224         """ 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:"""
00225         """ [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] """
00226         if len(end_effector_link) > 0 or self.has_end_effector_link():
00227             ok = False
00228             if type(pose) is PoseStamped:
00229                 old = self.get_pose_reference_frame()
00230                 self.set_pose_reference_frame(pose.header.frame_id)
00231                 ok = self._g.set_pose_target(conversions.pose_to_list(pose.pose), end_effector_link)
00232                 self.set_pose_reference_frame(old)
00233             elif type(pose) is Pose:
00234                 ok = self._g.set_pose_target(conversions.pose_to_list(pose), end_effector_link)
00235             else:
00236                 ok = self._g.set_pose_target(pose, end_effector_link)
00237             if not ok:
00238                 raise MoveItCommanderException("Unable to set target pose")
00239         else:
00240             raise MoveItCommanderException("There is no end effector to set the pose for")
00241 
00242     def set_pose_targets(self, poses, end_effector_link = ""):
00243         """ 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] """
00244         if len(end_effector_link) > 0 or self.has_end_effector_link():
00245             if not self._g.set_pose_targets([conversions.pose_to_list(p) if type(p) is Pose else p for p in poses], end_effector_link):
00246                 raise MoveItCommanderException("Unable to set target poses")
00247         else:
00248             raise MoveItCommanderException("There is no end effector to set poses for")
00249 
00250     def shift_pose_target(self, axis, value, end_effector_link = ""):
00251         """ 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 """
00252         if len(end_effector_link) > 0 or self.has_end_effector_link():
00253             pose = self._g.get_current_pose(end_effector_link)
00254             # by default we get orientation as a quaternion list
00255             # if we are updating a rotation axis however, we convert the orientation to RPY
00256             if axis > 2:
00257                 (r, p, y) = tf.transformations.euler_from_quaternion(pose[3:])
00258                 pose = [pose[0], pose[1], pose[2], r, p, y]
00259             if axis >= 0 and axis < 6:
00260                 pose[axis] = pose[axis] + value
00261                 self.set_pose_target(pose, end_effector_link)
00262             else:
00263                 raise MoveItCommanderException("An axis value between 0 and 5 expected")
00264         else:
00265             raise MoveItCommanderException("There is no end effector to set poses for")
00266 
00267     def clear_pose_target(self, end_effector_link):
00268         """ Clear the pose target for a particular end-effector """
00269         self._g.clear_pose_target(end_effector_link)
00270         
00271     def clear_pose_targets(self):
00272         """ Clear all known pose targets """
00273         self._g.clear_pose_targets()
00274 
00275     def set_random_target(self):
00276         """ Set a random joint configuration target """
00277         self._g.set_random_target()
00278 
00279     def set_named_target(self, name):
00280         """ 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. """
00281         if not self._g.set_named_target(name):
00282             raise MoveItCommanderException("Unable to set target %s. Is the target within bounds?" % name)
00283 
00284     def remember_joint_values(self, name, values = None):
00285         """ 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. """
00286         if values == None:
00287             values = self.get_current_joint_values()
00288         self._g.remember_joint_values(name, values)
00289 
00290     def get_remembered_joint_values(self):
00291         """ Get a dictionary that maps names to joint configurations for the group """
00292         return self._g.get_remembered_joint_values()
00293     
00294     def forget_joint_values(self, name):
00295         """ Forget a stored joint configuration """
00296         self._g.forget_joint_values(name)
00297 
00298     def get_goal_tolerance(self):
00299         """ Return a tuple of goal tolerances: joint, position and orientation. """
00300         return (self.get_goal_joint_tolerance(), self.get_goal_position_tolerance(), self.get_goal_orientation_tolerance())
00301 
00302     def get_goal_joint_tolerance(self):
00303         """ Get the tolerance for achieving a joint goal (distance for each joint variable) """
00304         return self._g.get_goal_joint_tolerance()
00305 
00306     def get_goal_position_tolerance(self):
00307         """ 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 """
00308         return self._g.get_goal_position_tolerance()
00309 
00310     def get_goal_orientation_tolerance(self):
00311         """ 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 """
00312         return self._g.get_goal_orientation_tolerance()
00313 
00314     def set_goal_tolerance(self, value):
00315         """ Set the joint, position and orientation goal tolerances simultaneously """
00316         self._g.set_goal_tolerance(value)
00317 
00318     def set_goal_joint_tolerance(self, value):
00319         """ Set the tolerance for a target joint configuration """
00320         self._g.set_goal_joint_tolerance(value)
00321 
00322     def set_goal_position_tolerance(self, value):
00323         """ Set the tolerance for a target end-effector position """
00324         self._g.set_goal_position_tolerance(value)
00325 
00326     def set_goal_orientation_tolerance(self, value):
00327         """ Set the tolerance for a target end-effector orientation """
00328         self._g.set_goal_orientation_tolerance(value)
00329 
00330     def allow_looking(self, value):
00331         """ Enable/disable looking around for motion planning """
00332         self._g.allow_looking(value)
00333 
00334     def allow_replanning(self, value):
00335         """ Enable/disable replanning """
00336         self._g.allow_replanning(value)
00337         
00338     def get_known_constraints(self):
00339         """ Get a list of names for the constraints specific for this group, as read from the warehouse """
00340         return self._g.get_known_constraints()
00341 
00342     def get_path_constraints(self):
00343         """ Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints """
00344         c = Constraints()
00345         c_str = self._g.get_path_constraints()
00346         conversions.msg_from_string(c,c_str)
00347         return c
00348 
00349     def set_path_constraints(self, value):
00350         """ Specify the path constraints to be used (as read from the database) """
00351         if value == None:
00352             self.clear_path_constraints()
00353         else:
00354             if type(value) is Constraints:
00355                 self._g.set_path_constraints_from_msg(conversions.msg_to_string(value))
00356             elif not self._g.set_path_constraints(value):
00357                 raise MoveItCommanderException("Unable to set path constraints " + value)
00358 
00359     def clear_path_constraints(self):
00360         """ Specify that no path constraints are to be used during motion planning """
00361         self._g.clear_path_constraints()
00362 
00363     def set_constraints_database(self, host, port):
00364         """ Specify which database to connect to for loading possible path constraints """
00365         self._g.set_constraints_database(host, port)
00366 
00367     def set_planning_time(self, seconds):
00368         """ Specify the amount of time to be used for motion planning. """
00369         self._g.set_planning_time(seconds)
00370 
00371     def get_planning_time(self):
00372         """ Specify the amount of time to be used for motion planning. """
00373         return self._g.get_planning_time()
00374 
00375     def set_planner_id(self, planner_id):
00376         """ Specify which planner to use when motion planning """
00377         self._g.set_planner_id(planner_id)
00378 
00379     def set_workspace(self, ws):
00380         """ Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ] """
00381         if len(ws) == 0:
00382             self._g.set_workspace(0.0, 0.0, 0.0, 0.0, 0.0, 0.0)
00383         else:
00384             if len(ws) == 4:
00385                 self._g.set_workspace(ws[0], ws[1], 0.0, ws[2], ws[3], 0.0)
00386             else:
00387                 if len(ws) == 6:
00388                     self._g.set_workspace(ws[0], ws[1], ws[2], ws[3], ws[4], ws[5])
00389                 else:
00390                     raise MoveItCommanderException("Expected 0, 4 or 6 values in list specifying workspace")
00391 
00392     def go(self, joints = None, wait = True):
00393         """ Set the target of the group and then move the group to the specified target """
00394         if type(joints) is bool:
00395             wait = joints
00396             joints = None
00397 
00398         elif type(joints) is JointState:
00399             self.set_joint_value_target(joints)
00400 
00401         elif type(joints) is Pose:
00402             self.set_pose_target(joints)
00403 
00404         elif not joints == None:
00405             try:
00406                 self.set_joint_value_target(self.get_remembered_joint_values()[joints])
00407             except:
00408                 self.set_joint_value_target(joints)
00409         if wait:
00410             return self._g.move()
00411         else:
00412             return self._g.async_move()
00413 
00414     def plan(self, joints = None):
00415         """ Return a motion plan (a RobotTrajectory) to the set goal state (or specified by the joints argument) """
00416         if type(joints) is JointState:
00417             self.set_joint_value_target(joints)
00418 
00419         elif type(joints) is Pose:
00420             self.set_pose_target(joints)
00421 
00422         elif not joints == None:
00423             try:
00424                 self.set_joint_value_target(self.get_remembered_joint_values()[joints])
00425             except:
00426                 self.set_joint_value_target(joints)
00427         plan = RobotTrajectory()
00428         plan.deserialize(self._g.compute_plan())
00429         return plan
00430 
00431     def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions = True):
00432         """ 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. """
00433         (ser_path, fraction) = self._g.compute_cartesian_path([conversions.pose_to_list(p) for p in waypoints], eef_step, jump_threshold, avoid_collisions)
00434         path = RobotTrajectory()
00435         path.deserialize(ser_path)
00436         return (path, fraction)
00437 
00438     def execute(self, plan_msg):
00439         """Execute a previously planned path"""
00440         return self._g.execute(conversions.msg_to_string(plan_msg))
00441 
00442     def attach_object(self, object_name, link_name = "", touch_links = []):
00443         """ 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."""
00444         return self._g.attach_object(object_name, link_name, touch_links)
00445 
00446     def detach_object(self, name = ""):
00447         """ 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."""
00448         return self._g.detach_object(name)
00449 
00450     def pick(self, object_name, grasp = []):
00451         """Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument."""
00452         if type(grasp) is Grasp:
00453             return self._g.pick(object_name, conversions.msg_to_string(grasp))
00454         else:
00455             return self._g.pick(object_name, [conversions.msg_to_string(x) for x in grasp])
00456 
00457     def place(self, object_name, location=None):
00458         """Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided"""
00459         result = False
00460         if location is None:
00461             result = self._g.place(object_name)
00462         elif type(location) is PoseStamped:
00463             old = self.get_pose_reference_frame()
00464             self.set_pose_reference_frame(location.header.frame_id)
00465             result = self._g.place(object_name, conversions.pose_to_list(location.pose))
00466             self.set_pose_reference_frame(old)
00467         elif type(location) is Pose:
00468             result = self._g.place(object_name, conversions.pose_to_list(location))
00469         elif type(location) is PlaceLocation:
00470             result = self._g.place(object_name, conversions.msg_to_string(location))
00471         else:
00472             raise MoveItCommanderException("Parameter location must be a Pose, PoseStamped or PlaceLocation object")
00473         return result
00474 
00475     def set_support_surface_name(self, value):
00476         """ Set the support surface name for a place operation """
00477         self._g.set_support_surface_name(value)


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