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
34 
35 from geometry_msgs.msg import Pose, PoseStamped
36 from moveit_msgs.msg import RobotTrajectory, Grasp, PlaceLocation, Constraints
37 from sensor_msgs.msg import JointState
38 import rospy
39 import tf
40 from moveit_ros_planning_interface import _moveit_move_group_interface
41 from exception import MoveItCommanderException
42 import conversions
43 
44 class MoveGroupCommander(object):
45  """
46  Execution of simple commands for a particular group
47  """
48 
49  def __init__(self, name, robot_description="robot_description"):
50  """ Specify the group name for which to construct this commander instance. Throws an exception if there is an initialization error. """
51  self._g = _moveit_move_group_interface.MoveGroupInterface(name, robot_description)
52 
53  def get_name(self):
54  """ Get the name of the group this instance was initialized for """
55  return self._g.get_name()
56 
57  def stop(self):
58  """ Stop the current execution, if any """
59  self._g.stop()
60 
61  def get_active_joints(self):
62  """ Get the active joints of this group """
63  return self._g.get_active_joints()
64 
65  def get_joints(self):
66  """ Get the joints of this group """
67  return self._g.get_joints()
68 
69  def get_variable_count(self):
70  """ Return the number of variables used to parameterize a state in this group (larger or equal to number of DOF)"""
71  return self._g.get_variable_count()
72 
74  """ Check if this group has a link that is considered to be an end effector """
75  return len(self._g.get_end_effector_link()) > 0
76 
78  """ Get the name of the link that is considered to be an end-effector. Return an empty string if there is no end-effector. """
79  return self._g.get_end_effector_link()
80 
81  def set_end_effector_link(self, link_name):
82  """ Set the name of the link to be considered as an end effector """
83  if not self._g.set_end_effector_link(link_name):
84  raise MoveItCommanderException("Unable to set end efector link")
85 
87  """ Get the reference frame assumed for poses of end-effectors """
88  return self._g.get_pose_reference_frame()
89 
90  def set_pose_reference_frame(self, reference_frame):
91  """ Set the reference frame to assume for poses of end-effectors """
92  self._g.set_pose_reference_frame(reference_frame)
93 
94  def get_planning_frame(self):
95  """ Get the name of the frame where all planning is performed """
96  return self._g.get_planning_frame()
97 
99  """ Get the current configuration of the group as a list (these are values published on /joint_states) """
100  return self._g.get_current_joint_values()
101 
102  def get_current_pose(self, end_effector_link = ""):
103  """ Get the current pose of the end-effector of the group. Throws an exception if there is not end-effector. """
104  if len(end_effector_link) > 0 or self.has_end_effector_link():
105  return conversions.list_to_pose_stamped(self._g.get_current_pose(end_effector_link), self.get_planning_frame())
106  else:
107  raise MoveItCommanderException("There is no end effector to get the pose of")
108 
109  def get_current_rpy(self, end_effector_link = ""):
110  """ Get a list of 3 elements defining the [roll, pitch, yaw] of the end-effector. Throws an exception if there is not end-effector. """
111  if len(end_effector_link) > 0 or self.has_end_effector_link():
112  return self._g.get_current_rpy(end_effector_link)
113  else:
114  raise MoveItCommanderException("There is no end effector to get the rpy of")
115 
117  return self._g.get_random_joint_values()
118 
119  def get_random_pose(self, end_effector_link = ""):
120  if len(end_effector_link) > 0 or self.has_end_effector_link():
121  return conversions.list_to_pose_stamped(self._g.get_random_pose(end_effector_link), self.get_planning_frame())
122  else:
123  raise MoveItCommanderException("There is no end effector to get the pose of")
124 
126  self._g.set_start_state_to_current_state()
127 
128  def set_start_state(self, msg):
129  """
130  Specify a start state for the group.
131 
132  Parameters
133  ----------
134  msg : moveit_msgs/RobotState
135 
136  Examples
137  --------
138  >>> from moveit_msgs.msg import RobotState
139  >>> from sensor_msgs.msg import JointState
140  >>> joint_state = JointState()
141  >>> joint_state.header = Header()
142  >>> joint_state.header.stamp = rospy.Time.now()
143  >>> joint_state.name = ['joint_a', 'joint_b']
144  >>> joint_state.position = [0.17, 0.34]
145  >>> moveit_robot_state = RobotState()
146  >>> moveit_robot_state.joint_state = joint_state
147  >>> group.set_start_state(moveit_robot_state)
148  """
149  self._g.set_start_state(conversions.msg_to_string(msg))
150 
152  return self._g.get_joint_value_target()
153 
154  def set_joint_value_target(self, arg1, arg2 = None, arg3 = None):
155  """
156  Specify a target joint configuration for the group.
157  - if the type of arg1 is one of the following: dict, list, JointState message, then no other arguments should be provided.
158  The dict should specify pairs of joint variable names and their target values, the list should specify all the variable values
159  for the group. The JointState message specifies the positions of some single-dof joints.
160  - 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
161  interpreted as setting a particular joint to a particular value.
162  - 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
163  be either string or bool. The string type argument is interpreted as the end-effector the pose is specified for (default is to use
164  the default end-effector), and the bool is used to decide whether the pose specified is approximate (default is false). This situation
165  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.
166  Instead, one IK solution will be computed first, and that will be sent to the planner.
167  """
168  if type(arg1) is JointState:
169  if (arg2 != None or arg3 != None):
170  raise MoveItCommanderException("Too many arguments specified")
171  if not self._g.set_joint_value_target_from_joint_state_message(conversions.msg_to_string(arg1)):
172  raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
173 
174  elif (type(arg1) is str):
175  if (arg2 == None):
176  raise MoveItCommanderException("Joint value expected when joint name specified")
177  if (arg3 != None):
178  raise MoveItCommanderException("Too many arguments specified")
179  if not self._g.set_joint_value_target(arg1, arg2):
180  raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
181 
182  elif (type(arg1) is PoseStamped) or (type(arg1) is Pose):
183  approx = False
184  eef = ""
185  if (arg2 != None):
186  if type(arg2) is str:
187  eef = arg2
188  else:
189  if type(arg2) is bool:
190  approx = arg2
191  else:
192  raise MoveItCommanderException("Unexpected type")
193  if (arg3 != None):
194  if type(arg3) is str:
195  eef = arg3
196  else:
197  if type(arg3) is bool:
198  approx = arg3
199  else:
200  raise MoveItCommanderException("Unexpected type")
201  r = False
202  if type(arg1) is PoseStamped:
203  r = self._g.set_joint_value_target_from_pose_stamped(conversions.msg_to_string(arg1), eef, approx)
204  else:
205  r = self._g.set_joint_value_target_from_pose(conversions.msg_to_string(arg1), eef, approx)
206  if not r:
207  if approx:
208  raise MoveItCommanderException("Error setting joint target. Does your IK solver support approximate IK?")
209  else:
210  raise MoveItCommanderException("Error setting joint target. Is IK running?")
211 
212  elif (hasattr(arg1, '__iter__')):
213  if (arg2 != None or arg3 != None):
214  raise MoveItCommanderException("Too many arguments specified")
215  if not self._g.set_joint_value_target(arg1):
216  raise MoveItCommanderException("Error setting joint target. Is the target within bounds?")
217 
218  else:
219  raise MoveItCommanderException("Unsupported argument of type %s" % type(arg1))
220 
221 
222  def set_rpy_target(self, rpy, end_effector_link = ""):
223  """ Specify a target orientation for the end-effector. Any position of the end-effector is acceptable."""
224  if len(end_effector_link) > 0 or self.has_end_effector_link():
225  if len(rpy) == 3:
226  if not self._g.set_rpy_target(rpy[0], rpy[1], rpy[2], end_effector_link):
227  raise MoveItCommanderException("Unable to set orientation target")
228  else:
229  raise MoveItCommanderException("Expected [roll, pitch, yaw]")
230  else:
231  raise MoveItCommanderException("There is no end effector to set the pose for")
232 
233  def set_orientation_target(self, q, 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(q) == 4:
237  if not self._g.set_orientation_target(q[0], q[1], q[2], q[3], end_effector_link):
238  raise MoveItCommanderException("Unable to set orientation target")
239  else:
240  raise MoveItCommanderException("Expected [qx, qy, qz, qw]")
241  else:
242  raise MoveItCommanderException("There is no end effector to set the pose for")
243 
244  def set_position_target(self, xyz, end_effector_link = ""):
245  """ Specify a target position for the end-effector. Any orientation of the end-effector is acceptable."""
246  if len(end_effector_link) > 0 or self.has_end_effector_link():
247  if not self._g.set_position_target(xyz[0], xyz[1], xyz[2], end_effector_link):
248  raise MoveItCommanderException("Unable to set position target")
249  else:
250  raise MoveItCommanderException("There is no end effector to set the pose for")
251 
252  def set_pose_target(self, pose, end_effector_link = ""):
253  """ 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:"""
254  """ [x, y, z, rot_x, rot_y, rot_z] or a list of 7 floats [x, y, z, qx, qy, qz, qw] """
255  if len(end_effector_link) > 0 or self.has_end_effector_link():
256  ok = False
257  if type(pose) is PoseStamped:
258  old = self.get_pose_reference_frame()
259  self.set_pose_reference_frame(pose.header.frame_id)
260  ok = self._g.set_pose_target(conversions.pose_to_list(pose.pose), end_effector_link)
261  self.set_pose_reference_frame(old)
262  elif type(pose) is Pose:
263  ok = self._g.set_pose_target(conversions.pose_to_list(pose), end_effector_link)
264  else:
265  ok = self._g.set_pose_target(pose, end_effector_link)
266  if not ok:
267  raise MoveItCommanderException("Unable to set target pose")
268  else:
269  raise MoveItCommanderException("There is no end effector to set the pose for")
270 
271  def set_pose_targets(self, poses, end_effector_link = ""):
272  """ 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] """
273  if len(end_effector_link) > 0 or self.has_end_effector_link():
274  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):
275  raise MoveItCommanderException("Unable to set target poses")
276  else:
277  raise MoveItCommanderException("There is no end effector to set poses for")
278 
279  def shift_pose_target(self, axis, value, end_effector_link = ""):
280  """ 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 """
281  if len(end_effector_link) > 0 or self.has_end_effector_link():
282  pose = self._g.get_current_pose(end_effector_link)
283  # by default we get orientation as a quaternion list
284  # if we are updating a rotation axis however, we convert the orientation to RPY
285  if axis > 2:
286  (r, p, y) = tf.transformations.euler_from_quaternion(pose[3:])
287  pose = [pose[0], pose[1], pose[2], r, p, y]
288  if axis >= 0 and axis < 6:
289  pose[axis] = pose[axis] + value
290  self.set_pose_target(pose, end_effector_link)
291  else:
292  raise MoveItCommanderException("An axis value between 0 and 5 expected")
293  else:
294  raise MoveItCommanderException("There is no end effector to set poses for")
295 
296  def clear_pose_target(self, end_effector_link):
297  """ Clear the pose target for a particular end-effector """
298  self._g.clear_pose_target(end_effector_link)
299 
301  """ Clear all known pose targets """
302  self._g.clear_pose_targets()
303 
304  def set_random_target(self):
305  """ Set a random joint configuration target """
306  self._g.set_random_target()
307 
308  def set_named_target(self, name):
309  """ 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. """
310  if not self._g.set_named_target(name):
311  raise MoveItCommanderException("Unable to set target %s. Is the target within bounds?" % name)
312 
313  def remember_joint_values(self, name, values = None):
314  """ 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. """
315  if values == None:
316  values = self.get_current_joint_values()
317  self._g.remember_joint_values(name, values)
318 
320  """ Get a dictionary that maps names to joint configurations for the group """
321  return self._g.get_remembered_joint_values()
322 
323  def forget_joint_values(self, name):
324  """ Forget a stored joint configuration """
325  self._g.forget_joint_values(name)
326 
328  """ Return a tuple of goal tolerances: joint, position and orientation. """
330 
332  """ Get the tolerance for achieving a joint goal (distance for each joint variable) """
333  return self._g.get_goal_joint_tolerance()
334 
336  """ 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 """
337  return self._g.get_goal_position_tolerance()
338 
340  """ 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 """
341  return self._g.get_goal_orientation_tolerance()
342 
343  def set_goal_tolerance(self, value):
344  """ Set the joint, position and orientation goal tolerances simultaneously """
345  self._g.set_goal_tolerance(value)
346 
347  def set_goal_joint_tolerance(self, value):
348  """ Set the tolerance for a target joint configuration """
349  self._g.set_goal_joint_tolerance(value)
350 
351  def set_goal_position_tolerance(self, value):
352  """ Set the tolerance for a target end-effector position """
353  self._g.set_goal_position_tolerance(value)
354 
356  """ Set the tolerance for a target end-effector orientation """
357  self._g.set_goal_orientation_tolerance(value)
358 
359  def allow_looking(self, value):
360  """ Enable/disable looking around for motion planning """
361  self._g.allow_looking(value)
362 
363  def allow_replanning(self, value):
364  """ Enable/disable replanning """
365  self._g.allow_replanning(value)
366 
368  """ Get a list of names for the constraints specific for this group, as read from the warehouse """
369  return self._g.get_known_constraints()
370 
372  """ Get the acutal path constraints in form of a moveit_msgs.msgs.Constraints """
373  c = Constraints()
374  c_str = self._g.get_path_constraints()
375  conversions.msg_from_string(c,c_str)
376  return c
377 
378  def set_path_constraints(self, value):
379  """ Specify the path constraints to be used (as read from the database) """
380  if value == None:
382  else:
383  if type(value) is Constraints:
384  self._g.set_path_constraints_from_msg(conversions.msg_to_string(value))
385  elif not self._g.set_path_constraints(value):
386  raise MoveItCommanderException("Unable to set path constraints " + value)
387 
389  """ Specify that no path constraints are to be used during motion planning """
390  self._g.clear_path_constraints()
391 
392  def set_constraints_database(self, host, port):
393  """ Specify which database to connect to for loading possible path constraints """
394  self._g.set_constraints_database(host, port)
395 
396  def set_planning_time(self, seconds):
397  """ Specify the amount of time to be used for motion planning. """
398  self._g.set_planning_time(seconds)
399 
400  def get_planning_time(self):
401  """ Specify the amount of time to be used for motion planning. """
402  return self._g.get_planning_time()
403 
404  def set_planner_id(self, planner_id):
405  """ Specify which planner to use when motion planning """
406  self._g.set_planner_id(planner_id)
407 
408  def set_num_planning_attempts(self, num_planning_attempts):
409  """ 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. """
410  self._g.set_num_planning_attempts(num_planning_attempts)
411 
412  def set_workspace(self, ws):
413  """ Set the workspace for the robot as either [], [minX, minY, maxX, maxY] or [minX, minY, minZ, maxX, maxY, maxZ] """
414  if len(ws) == 0:
415  self._g.set_workspace(0.0, 0.0, 0.0, 0.0, 0.0, 0.0)
416  else:
417  if len(ws) == 4:
418  self._g.set_workspace(ws[0], ws[1], 0.0, ws[2], ws[3], 0.0)
419  else:
420  if len(ws) == 6:
421  self._g.set_workspace(ws[0], ws[1], ws[2], ws[3], ws[4], ws[5])
422  else:
423  raise MoveItCommanderException("Expected 0, 4 or 6 values in list specifying workspace")
424 
426  """ Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,1]. """
427  if value > 0 and value <= 1:
428  self._g.set_max_velocity_scaling_factor(value)
429  else:
430  raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor" )
431 
433  """ Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0,1]. """
434  if value > 0 and value <= 1:
435  self._g.set_max_acceleration_scaling_factor(value)
436  else:
437  raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor" )
438 
439  def go(self, joints = None, wait = True):
440  """ Set the target of the group and then move the group to the specified target """
441  if type(joints) is bool:
442  wait = joints
443  joints = None
444 
445  elif type(joints) is JointState:
446  self.set_joint_value_target(joints)
447 
448  elif type(joints) is Pose:
449  self.set_pose_target(joints)
450 
451  elif not joints == None:
452  try:
454  except:
455  self.set_joint_value_target(joints)
456  if wait:
457  return self._g.move()
458  else:
459  return self._g.async_move()
460 
461  def plan(self, joints = None):
462  """ Return a motion plan (a RobotTrajectory) to the set goal state (or specified by the joints argument) """
463  if type(joints) is JointState:
464  self.set_joint_value_target(joints)
465 
466  elif type(joints) is Pose:
467  self.set_pose_target(joints)
468 
469  elif not joints == None:
470  try:
472  except:
473  self.set_joint_value_target(joints)
474  plan = RobotTrajectory()
475  plan.deserialize(self._g.compute_plan())
476  return plan
477 
478  def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions = True):
479  """ 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. """
480  (ser_path, fraction) = self._g.compute_cartesian_path([conversions.pose_to_list(p) for p in waypoints], eef_step, jump_threshold, avoid_collisions)
481  path = RobotTrajectory()
482  path.deserialize(ser_path)
483  return (path, fraction)
484 
485  def execute(self, plan_msg, wait = True):
486  """Execute a previously planned path"""
487  if wait:
488  return self._g.execute(conversions.msg_to_string(plan_msg))
489  else:
490  return self._g.async_execute(conversions.msg_to_string(plan_msg))
491 
492  def attach_object(self, object_name, link_name = "", touch_links = []):
493  """ 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."""
494  return self._g.attach_object(object_name, link_name, touch_links)
495 
496  def detach_object(self, name = ""):
497  """ 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."""
498  return self._g.detach_object(name)
499 
500  def pick(self, object_name, grasp = []):
501  """Pick the named object. A grasp message, or a list of Grasp messages can also be specified as argument."""
502  if type(grasp) is Grasp:
503  return self._g.pick(object_name, conversions.msg_to_string(grasp))
504  else:
505  return self._g.pick(object_name, [conversions.msg_to_string(x) for x in grasp])
506 
507  def place(self, object_name, location=None):
508  """Place the named object at a particular location in the environment or somewhere safe in the world if location is not provided"""
509  result = False
510  if location is None:
511  result = self._g.place(object_name)
512  elif type(location) is PoseStamped:
513  old = self.get_pose_reference_frame()
514  self.set_pose_reference_frame(location.header.frame_id)
515  result = self._g.place(object_name, conversions.pose_to_list(location.pose))
516  self.set_pose_reference_frame(old)
517  elif type(location) is Pose:
518  result = self._g.place(object_name, conversions.pose_to_list(location))
519  elif type(location) is PlaceLocation:
520  result = self._g.place(object_name, conversions.msg_to_string(location))
521  else:
522  raise MoveItCommanderException("Parameter location must be a Pose, PoseStamped or PlaceLocation object")
523  return result
524 
525  def set_support_surface_name(self, value):
526  """ Set the support surface name for a place operation """
527  self._g.set_support_surface_name(value)
528 
529  def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor):
530  ser_ref_state_in = conversions.msg_to_string(ref_state_in)
531  ser_traj_in = conversions.msg_to_string(traj_in)
532  ser_traj_out = self._g.retime_trajectory(ser_ref_state_in, ser_traj_in, velocity_scaling_factor)
533  traj_out = RobotTrajectory()
534  traj_out.deserialize(ser_traj_out)
535  return traj_out
def shift_pose_target(self, axis, value, end_effector_link="")
Definition: move_group.py:279
def execute(self, plan_msg, wait=True)
Definition: move_group.py:485
def set_pose_reference_frame(self, reference_frame)
Definition: move_group.py:90
def pick(self, object_name, grasp=[])
Definition: move_group.py:500
def remember_joint_values(self, name, values=None)
Definition: move_group.py:313
def compute_cartesian_path(self, waypoints, eef_step, jump_threshold, avoid_collisions=True)
Definition: move_group.py:478
def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor)
Definition: move_group.py:529
def get_current_rpy(self, end_effector_link="")
Definition: move_group.py:109
def __init__(self, name, robot_description="robot_description")
Definition: move_group.py:49
def clear_pose_target(self, end_effector_link)
Definition: move_group.py:296
def get_random_pose(self, end_effector_link="")
Definition: move_group.py:119
def get_current_pose(self, end_effector_link="")
Definition: move_group.py:102
def set_rpy_target(self, rpy, end_effector_link="")
Definition: move_group.py:222
def set_pose_target(self, pose, end_effector_link="")
Definition: move_group.py:252
def set_orientation_target(self, q, end_effector_link="")
Definition: move_group.py:233
def set_position_target(self, xyz, end_effector_link="")
Definition: move_group.py:244
def set_num_planning_attempts(self, num_planning_attempts)
Definition: move_group.py:408
def go(self, joints=None, wait=True)
Definition: move_group.py:439
def set_joint_value_target(self, arg1, arg2=None, arg3=None)
Definition: move_group.py:154
def place(self, object_name, location=None)
Definition: move_group.py:507
def set_pose_targets(self, poses, end_effector_link="")
Definition: move_group.py:271
def attach_object(self, object_name, link_name="", touch_links=[])
Definition: move_group.py:492


moveit_commander
Author(s): Ioan Sucan
autogenerated on Sun Jan 21 2018 03:56:14