move_group.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Author: Ioan Sucan, William Baker
34 
35 from geometry_msgs.msg import Pose, PoseStamped
36 from moveit_msgs.msg import RobotTrajectory, Grasp, PlaceLocation, Constraints, RobotState
37 from moveit_msgs.msg import MoveItErrorCodes, TrajectoryConstraints, PlannerInterfaceDescription
38 from sensor_msgs.msg import JointState
39 import rospy
40 import tf
41 from moveit_ros_planning_interface import _moveit_move_group_interface
42 from .exception import MoveItCommanderException
43 import moveit_commander.conversions as conversions
44 
45 class MoveGroupCommander(object):
46  """
47  Execution of simple commands for a particular group
48  """
49 
50  def __init__(self, name, robot_description="robot_description", ns=""):
51  """ Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error. """
52  self._g = _moveit_move_group_interface.MoveGroupInterface(name, robot_description, ns)
53 
54  def get_name(self):
55  """ Get the name of the group this instance was initialized for """
56  return self._g.get_name()
57 
58  def stop(self):
59  """ Stop the current execution, if any """
60  self._g.stop()
61 
62  def get_active_joints(self):
63  """ Get the active joints of this group """
64  return self._g.get_active_joints()
65 
66  def get_joints(self):
67  """ Get the joints of this group """
68  return self._g.get_joints()
69 
70  def get_variable_count(self):
71  """ Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)"""
72  return self._g.get_variable_count()
73 
75  """ Check if this group has a link that is considered to be an end effector """
76  return len(self._g.get_end_effector_link()) > 0
77 
79  """ Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector. """
80  return self._g.get_end_effector_link()
81 
82  def set_end_effector_link(self, link_name):
83  """ Set the name of the link to be considered as an end effector """
84  if not self._g.set_end_effector_link(link_name):
85  raise MoveItCommanderException("Unable to set end efector link")
86 
88  """ Get the description of the planner interface (list of planner ids) """
89  desc = PlannerInterfaceDescription()
90  conversions.msg_from_string(desc, self._g.get_interface_description())
91  return desc
92 
94  """ Get the reference frame assumed for poses of end-effectors """
95  return self._g.get_pose_reference_frame()
96 
97  def set_pose_reference_frame(self, reference_frame):
98  """ Set the reference frame to assume for poses of end-effectors """
99  self._g.set_pose_reference_frame(reference_frame)
100 
102  """ Get the name of the frame where all planning is performed """
103  return self._g.get_planning_frame()
104 
106  """ Get the current configuration of the group as a list (these are values published on /joint_states) """
107  return self._g.get_current_joint_values()
108 
109  def get_current_pose(self, end_effector_link = ""):
110  """ Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector. """
111  if len(end_effector_link) > 0 or self.has_end_effector_link():
112  return conversions.list_to_pose_stamped(self._g.get_current_pose(end_effector_link), self.get_planning_frame())
113  else:
114  raise MoveItCommanderException("There is no end effector to get the pose of")
115 
116  def get_current_rpy(self, end_effector_link = ""):
117  """ Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector. """
118  if len(end_effector_link) > 0 or self.has_end_effector_link():
119  return self._g.get_current_rpy(end_effector_link)
120  else:
121  raise MoveItCommanderException("There is no end effector to get the rpy of")
122 
124  return self._g.get_random_joint_values()
125 
126  def get_random_pose(self, end_effector_link = ""):
127  if len(end_effector_link) > 0 or self.has_end_effector_link():
128  return conversions.list_to_pose_stamped(self._g.get_random_pose(end_effector_link), self.get_planning_frame())
129  else:
130  raise MoveItCommanderException("There is no end effector to get the pose of")
131 
133  self._g.set_start_state_to_current_state()
134 
135  def set_start_state(self, msg):
136  """
137  Specify a start state for the group.
138 
139  Parameters
140  ----------
141  msg : moveit_msgs/RobotState
142 
143  Examples
144  --------
145  >>> from moveit_msgs.msg import RobotState
146  >>> from sensor_msgs.msg import JointState
147  >>> joint_state = JointState()
148  >>> joint_state.header = Header()
149  >>> joint_state.header.stamp = rospy.Time.now()
150  >>> joint_state.name = ['joint_a', 'joint_b']
151  >>> joint_state.position = [0.17, 0.34]
152  >>> moveit_robot_state = RobotState()
153  >>> moveit_robot_state.joint_state = joint_state
154  >>> group.set_start_state(moveit_robot_state)
155  """
156  self._g.set_start_state(conversions.msg_to_string(msg))
157 
159  return self._g.get_joint_value_target()
160 
161  def set_joint_value_target(self, arg1, arg2 = None, arg3 = None):
162  """
163  Specify a target joint configuration for the group.
164  - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided.
165  The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values
166  for the group. The JointState message specifies the positions of some single-dof joints.
167  - 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
168  interpreted as setting a particular joint to a particular value.
169  - 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
170  be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use
171  the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation
172  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.
173  Instead, one IK solution will be computed first, and that will be sent to the planner.
174  """
175  if isinstance(arg1, RobotState):
176  if not self._g.set_state_value_target(conversions.msg_to_string(arg1)):
177  raise MoveItCommanderException("Error setting state target. Is the target state within bounds?")
178 
179  elif isinstance(arg1, JointState):
180  if (arg2 is not None or arg3 is not None):
181  raise MoveItCommanderException("Too many arguments specified")
182  if not self._g.set_joint_value_target_from_joint_state_message(conversions.msg_to_string(arg1)):
183  raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
184 
185  elif isinstance(arg1, str):
186  if (arg2 is None):
187  raise MoveItCommanderException("Joint value expected when joint name specified")
188  if (arg3 is not None):
189  raise MoveItCommanderException("Too many arguments specified")
190  if not self._g.set_joint_value_target(arg1, arg2):
191  raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
192 
193  elif isinstance(arg1, (Pose, PoseStamped)):
194  approx = False
195  eef = ""
196  if (arg2 is not None):
197  if type(arg2) is str:
198  eef = arg2
199  else:
200  if type(arg2) is bool:
201  approx = arg2
202  else:
203  raise MoveItCommanderException("Unexpected type")
204  if (arg3 is not None):
205  if type(arg3) is str:
206  eef = arg3
207  else:
208  if type(arg3) is bool:
209  approx = arg3
210  else:
211  raise MoveItCommanderException("Unexpected type")
212  r = False
213  if type(arg1) is PoseStamped:
214  r = self._g.set_joint_value_target_from_pose_stamped(conversions.msg_to_string(arg1), eef, approx)
215  else:
216  r = self._g.set_joint_value_target_from_pose(conversions.msg_to_string(arg1), eef, approx)
217  if not r:
218  if approx:
219  raise MoveItCommanderException("Error setting joint target. Does your IK solver support approximate IK?")
220  else:
221  raise MoveItCommanderException("Error setting joint target. Is IK running?")
222 
223  elif (hasattr(arg1, '__iter__')):
224  if (arg2 is not None or arg3 is not None):
225  raise MoveItCommanderException("Too many arguments specified")
226  if not self._g.set_joint_value_target(arg1):
227  raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
228 
229  else:
230  raise MoveItCommanderException("Unsupported argument of type %s" % type(arg1))
231 
232 
233  def set_rpy_target(self, rpy, end_effector_link = ""):
234  """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
235  if len(end_effector_link) > 0 or self.has_end_effector_link():
236  if len(rpy) == 3:
237  if not self._g.set_rpy_target(rpy[0], rpy[1], rpy[2], end_effector_link):
238  raise MoveItCommanderException("Unable to set orientation target")
239  else:
240  raise MoveItCommanderException("Expected [roll, pitch, yaw]")
241  else:
242  raise MoveItCommanderException("There is no end effector to set the pose for")
243 
244  def set_orientation_target(self, q, end_effector_link = ""):
245  """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
246  if len(end_effector_link) > 0 or self.has_end_effector_link():
247  if len(q) == 4:
248  if not self._g.set_orientation_target(q[0], q[1], q[2], q[3], end_effector_link):
249  raise MoveItCommanderException("Unable to set orientation target")
250  else:
251  raise MoveItCommanderException("Expected [qx, qy, qz, qw]")
252  else:
253  raise MoveItCommanderException("There is no end effector to set the pose for")
254 
255  def set_position_target(self, xyz, end_effector_link = ""):
256  """ Specify a target position for the end-effector. Any orientation of the end-effector is acceptable."""
257  if len(end_effector_link) > 0 or self.has_end_effector_link():
258  if not self._g.set_position_target(xyz[0], xyz[1], xyz[2], end_effector_link):
259  raise MoveItCommanderException("Unable to set position target")
260  else:
261  raise MoveItCommanderException("There is no end effector to set the pose for")
262 
263  def set_pose_target(self, pose, end_effector_link = ""):
264  """ 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:"""
265  """ [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] """
266  if len(end_effector_link) > 0 or self.has_end_effector_link():
267  ok = False
268  if type(pose) is PoseStamped:
269  old = self.get_pose_reference_frame()
270  self.set_pose_reference_frame(pose.header.frame_id)
271  ok = self._g.set_pose_target(conversions.pose_to_list(pose.pose), end_effector_link)
272  self.set_pose_reference_frame(old)
273  elif type(pose) is Pose:
274  ok = self._g.set_pose_target(conversions.pose_to_list(pose), end_effector_link)
275  else:
276  ok = self._g.set_pose_target(pose, end_effector_link)
277  if not ok:
278  raise MoveItCommanderException("Unable to set target pose")
279  else:
280  raise MoveItCommanderException("There is no end effector to set the pose for")
281 
282  def set_pose_targets(self, poses, end_effector_link = ""):
283  """ 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] """
284  if len(end_effector_link) > 0 or self.has_end_effector_link():
285  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):
286  raise MoveItCommanderException("Unable to set target poses")
287  else:
288  raise MoveItCommanderException("There is no end effector to set poses for")
289 
290  def shift_pose_target(self, axis, value, end_effector_link = ""):
291  """ 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 """
292  if len(end_effector_link) > 0 or self.has_end_effector_link():
293  pose = self._g.get_current_pose(end_effector_link)
294  # by default we get orientation as a quaternion list
295  # if we are updating a rotation axis however, we convert the orientation to RPY
296  if axis > 2:
297  (r, p, y) = tf.transformations.euler_from_quaternion(pose[3:])
298  pose = [pose[0], pose[1], pose[2], r, p, y]
299  if axis >= 0 and axis < 6:
300  pose[axis] = pose[axis] + value
301  self.set_pose_target(pose, end_effector_link)
302  else:
303  raise MoveItCommanderException("An axis value between 0 and 5 expected")
304  else:
305  raise MoveItCommanderException("There is no end effector to set poses for")
306 
307  def clear_pose_target(self, end_effector_link):
308  """ Clear the pose target for a particular end-effector """
309  self._g.clear_pose_target(end_effector_link)
310 
312  """ Clear all known pose targets """
313  self._g.clear_pose_targets()
314 
315  def set_random_target(self):
316  """ Set a random joint configuration target """
317  self._g.set_random_target()
318 
319  def get_named_targets(self):
320  """ Get a list of all the names of joint configurations."""
321  return self._g.get_named_targets()
322 
323  def set_named_target(self, name):
324  """ 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. """
325  if not self._g.set_named_target(name):
326  raise MoveItCommanderException("Unable to set target %s. Is the target within bounds?" % name)
327 
328  def get_named_target_values(self, target):
329  """Get a dictionary of joint values of a named target"""
330  return self._g.get_named_target_values(target)
331 
332  def remember_joint_values(self, name, values = None):
333  """ 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. """
334  if values is None:
335  values = self.get_current_joint_values()
336  self._g.remember_joint_values(name, values)
337 
339  """ Get a dictionary that maps names to joint configurations for the group """
340  return self._g.get_remembered_joint_values()
341 
342  def forget_joint_values(self, name):
343  """ Forget a stored joint configuration """
344  self._g.forget_joint_values(name)
345 
347  """ Return a tuple of goal tolerances: joint, position and orientation. """
349 
351  """ Get the tolerance for achieving a joint goal (distance for each joint variable) """
352  return self._g.get_goal_joint_tolerance()
353 
355  """ 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 """
356  return self._g.get_goal_position_tolerance()
357 
359  """ 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 """
360  return self._g.get_goal_orientation_tolerance()
361 
362  def set_goal_tolerance(self, value):
363  """ Set the joint, position and orientation goal tolerances simultaneously """
364  self._g.set_goal_tolerance(value)
365 
366  def set_goal_joint_tolerance(self, value):
367  """ Set the tolerance for a target joint configuration """
368  self._g.set_goal_joint_tolerance(value)
369 
370  def set_goal_position_tolerance(self, value):
371  """ Set the tolerance for a target end-effector position """
372  self._g.set_goal_position_tolerance(value)
373 
375  """ Set the tolerance for a target end-effector orientation """
376  self._g.set_goal_orientation_tolerance(value)
377 
378  def allow_looking(self, value):
379  """ Enable/disable looking around for motion planning """
380  self._g.allow_looking(value)
381 
382  def allow_replanning(self, value):
383  """ Enable/disable replanning """
384  self._g.allow_replanning(value)
385 
387  """ Get a list of names for the constraints specific for this group, as read from the warehouse """
388  return self._g.get_known_constraints()
389 
391  """ Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints """
392  c = Constraints()
393  c_str = self._g.get_path_constraints()
394  conversions.msg_from_string(c,c_str)
395  return c
396 
397  def set_path_constraints(self, value):
398  """ Specify the path constraints to be used (as read from the database) """
399  if value is None:
401  else:
402  if type(value) is Constraints:
403  self._g.set_path_constraints_from_msg(conversions.msg_to_string(value))
404  elif not self._g.set_path_constraints(value):
405  raise MoveItCommanderException("Unable to set path constraints " + value)
406 
408  """ Specify that no path constraints are to be used during motion planning """
409  self._g.clear_path_constraints()
410 
412  """ Get the actual trajectory constraints in form of a moveit_msgs.msgs.Constraints """
413  c = Constraints()
414  c_str = self._g.get_trajectory_constraints()
415  conversions.msg_from_string(c, c_str)
416  return c
417 
418  def set_trajectory_constraints(self, value):
419  """ Specify the trajectory constraints to be used """
420  if value is None:
422  else:
423  if type(value) is TrajectoryConstraints:
424  self._g.set_trajectory_constraints_from_msg(conversions.msg_to_string(value))
425  elif not self._g.set_trajectory_constraints(value):
426  raise MoveItCommanderException("Unable to set trajectory constraints " + value)
427 
429  """ Specify that no trajectory constraints are to be used during motion planning """
430  self._g.clear_trajectory_constraints()
431 
432  def set_constraints_database(self, host, port):
433  """ Specify which database to connect to for loading possible path constraints """
434  self._g.set_constraints_database(host, port)
435 
436  def set_planning_time(self, seconds):
437  """ Specify the amount of time to be used for motion planning. """
438  self._g.set_planning_time(seconds)
439 
440  def get_planning_time(self):
441  """ Specify the amount of time to be used for motion planning. """
442  return self._g.get_planning_time()
443 
444  def set_planner_id(self, planner_id):
445  """ Specify which planner to use when motion planning """
446  self._g.set_planner_id(planner_id)
447 
448  def get_planner_id(self):
449  """ Get the current planner_id """
450  self._g.get_planner_id()
451 
452  def set_num_planning_attempts(self, num_planning_attempts):
453  """ Set the number of times the motion plan is to be computed from scratch before the shortest solution is returned. The default value is 1. """
454  self._g.set_num_planning_attempts(num_planning_attempts)
455 
456  def set_workspace(self, ws):
457  """ Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ] """
458  if len(ws) == 0:
459  self._g.set_workspace(0.0, 0.0, 0.0, 0.0, 0.0, 0.0)
460  else:
461  if len(ws) == 4:
462  self._g.set_workspace(ws[0], ws[1], 0.0, ws[2], ws[3], 0.0)
463  else:
464  if len(ws) == 6:
465  self._g.set_workspace(ws[0], ws[1], ws[2], ws[3], ws[4], ws[5])
466  else:
467  raise MoveItCommanderException("Expected 0, 4 or 6 values in list specifying workspace")
468 
470  """ Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,1]. """
471  if value > 0 and value <= 1:
472  self._g.set_max_velocity_scaling_factor(value)
473  else:
474  raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor" )
475 
477  """ Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0,1]. """
478  if value > 0 and value <= 1:
479  self._g.set_max_acceleration_scaling_factor(value)
480  else:
481  raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor" )
482 
483  def go(self, joints = None, wait = True):
484  """ Set the target of the group and then move the group to the specified target """
485  if type(joints) is bool:
486  wait = joints
487  joints = None
488 
489  elif type(joints) is JointState:
490  self.set_joint_value_target(joints)
491 
492  elif type(joints) is Pose:
493  self.set_pose_target(joints)
494 
495  elif not joints is None:
496  try:
498  except:
499  self.set_joint_value_target(joints)
500  if wait:
501  return self._g.move()
502  else:
503  return self._g.async_move()
504 
505  def plan(self, joints = None):
506  """ Return a motion plan (a RobotTrajectory) to the set goal state (or specified by the joints argument) """
507  if type(joints) is JointState:
508  self.set_joint_value_target(joints)
509 
510  elif type(joints) is Pose:
511  self.set_pose_target(joints)
512 
513  elif not joints is None:
514  try:
516  except:
517  self.set_joint_value_target(joints)
518  plan = RobotTrajectory()
519  plan.deserialize(self._g.compute_plan())
520  return plan
521 
522  def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions = True, path_constraints = None):
523  """ 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; Kinematic constraints for the path given by path_constraints will be met for every point along the trajectory, if they are not met, a partial solution will be returned. The return value is a tuple: a fraction of how much of the path was followed, the actual RobotTrajectory. """
524  if path_constraints:
525  if type(path_constraints) is Constraints:
526  constraints_str = conversions.msg_to_string(path_constraints)
527  else:
528  raise MoveItCommanderException("Unable to set path constraints, unknown constraint type " + type(path_constraints))
529  (ser_path, fraction) = self._g.compute_cartesian_path([conversions.pose_to_list(p) for p in waypoints], eef_step, jump_threshold, avoid_collisions, constraints_str)
530  else:
531  (ser_path, fraction) = self._g.compute_cartesian_path([conversions.pose_to_list(p) for p in waypoints], eef_step, jump_threshold, avoid_collisions)
532 
533  path = RobotTrajectory()
534  path.deserialize(ser_path)
535  return (path, fraction)
536 
537  def execute(self, plan_msg, wait = True):
538  """Execute a previously planned path"""
539  if wait:
540  return self._g.execute(conversions.msg_to_string(plan_msg))
541  else:
542  return self._g.async_execute(conversions.msg_to_string(plan_msg))
543 
544  def attach_object(self, object_name, link_name = "", touch_links = []):
545  """ 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."""
546  return self._g.attach_object(object_name, link_name, touch_links)
547 
548  def detach_object(self, name = ""):
549  """ 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."""
550  return self._g.detach_object(name)
551 
552  def pick(self, object_name, grasp = [], plan_only=False):
553  """Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument."""
554  if type(grasp) is Grasp:
555  return self._g.pick(object_name, conversions.msg_to_string(grasp), plan_only)
556  else:
557  return self._g.pick(object_name, [conversions.msg_to_string(x) for x in grasp], plan_only)
558 
559  def place(self, object_name, location=None, plan_only=False):
560  """Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided"""
561  result = False
562  if location is None:
563  result = self._g.place(object_name, plan_only)
564  elif type(location) is PoseStamped:
565  old = self.get_pose_reference_frame()
566  self.set_pose_reference_frame(location.header.frame_id)
567  result = self._g.place(object_name, conversions.pose_to_list(location.pose), plan_only)
568  self.set_pose_reference_frame(old)
569  elif type(location) is Pose:
570  result = self._g.place(object_name, conversions.pose_to_list(location), plan_only)
571  elif type(location) is PlaceLocation:
572  result = self._g.place(object_name, conversions.msg_to_string(location), plan_only)
573  else:
574  raise MoveItCommanderException("Parameter location must be a Pose, PoseStamped or PlaceLocation object")
575  return result
576 
577  def set_support_surface_name(self, value):
578  """ Set the support surface name for a place operation """
579  self._g.set_support_surface_name(value)
580 
581  def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor):
582  ser_ref_state_in = conversions.msg_to_string(ref_state_in)
583  ser_traj_in = conversions.msg_to_string(traj_in)
584  ser_traj_out = self._g.retime_trajectory(ser_ref_state_in, ser_traj_in, velocity_scaling_factor)
585  traj_out = RobotTrajectory()
586  traj_out.deserialize(ser_traj_out)
587  return traj_out
588 
589  def get_jacobian_matrix(self, joint_values):
590  """ Get the jacobian matrix of the group as a list"""
591  return self._g.get_jacobian_matrix(joint_values)
def shift_pose_target(self, axis, value, end_effector_link="")
Definition: move_group.py:290
def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions=True, path_constraints=None)
Definition: move_group.py:522
def execute(self, plan_msg, wait=True)
Definition: move_group.py:537
def set_pose_reference_frame(self, reference_frame)
Definition: move_group.py:97
def remember_joint_values(self, name, values=None)
Definition: move_group.py:332
def __init__(self, name, robot_description="robot_description", ns="")
Definition: move_group.py:50
def pick(self, object_name, grasp=[], plan_only=False)
Definition: move_group.py:552
def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor)
Definition: move_group.py:581
def get_current_rpy(self, end_effector_link="")
Definition: move_group.py:116
def clear_pose_target(self, end_effector_link)
Definition: move_group.py:307
def get_random_pose(self, end_effector_link="")
Definition: move_group.py:126
def get_current_pose(self, end_effector_link="")
Definition: move_group.py:109
def set_rpy_target(self, rpy, end_effector_link="")
Definition: move_group.py:233
def set_pose_target(self, pose, end_effector_link="")
Definition: move_group.py:263
def set_orientation_target(self, q, end_effector_link="")
Definition: move_group.py:244
def set_position_target(self, xyz, end_effector_link="")
Definition: move_group.py:255
def set_num_planning_attempts(self, num_planning_attempts)
Definition: move_group.py:452
def go(self, joints=None, wait=True)
Definition: move_group.py:483
def place(self, object_name, location=None, plan_only=False)
Definition: move_group.py:559
def set_joint_value_target(self, arg1, arg2=None, arg3=None)
Definition: move_group.py:161
def set_pose_targets(self, poses, end_effector_link="")
Definition: move_group.py:282
def attach_object(self, object_name, link_name="", touch_links=[])
Definition: move_group.py:544


moveit_commander
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:56