move_group_interface.py
Go to the documentation of this file.
1 # Copyright 2011-2014, Michael Ferguson
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions
6 # are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above
11 # copyright notice, this list of conditions and the following
12 # disclaimer in the documentation and/or other materials provided
13 # with the distribution.
14 #
15 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
16 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
17 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
18 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
19 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
20 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
21 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
23 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
24 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
25 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 # POSSIBILITY OF SUCH DAMAGE.
27 
28 import rospy
29 import actionlib
30 from tf.listener import TransformListener
31 from geometry_msgs.msg import *
32 from moveit_msgs.msg import MoveGroupAction, MoveGroupGoal
33 from moveit_msgs.msg import Constraints, JointConstraint, PositionConstraint, OrientationConstraint, BoundingVolume
34 from shape_msgs.msg import SolidPrimitive
35 
36 
37 ## @brief Pure python interface to move_group action
38 class MoveGroupInterface(object):
39 
40  ## @brief Constructor for this utility
41  ## @param group Name of the MoveIt! group to command
42  ## @param frame Name of the fixed frame in which planning happens
43  ## @param listener A TF listener instance (optional, will create a new one if None)
44  ## @param plan_only Should we only plan, but not execute?
45  def __init__(self, group, frame, listener=None, plan_only=False):
46  self._group = group
47  self._fixed_frame = frame
49  MoveGroupAction)
50  self._action.wait_for_server()
51  if listener == None:
52  self._listener = TransformListener()
53  else:
54  self._listener = listener
55  self.plan_only = plan_only
56  self.planner_id = None
57  self.planning_time = 15.0
58 
59  def get_move_action(self):
60  return self._action
61 
62  ## @brief Move the arm to set of joint position goals
63  def moveToJointPosition(self,
64  joints,
65  positions,
66  tolerance=0.01,
67  wait=True,
68  **kwargs):
69  # Check arguments
70  supported_args = ("max_velocity_scaling_factor",
71  "planner_id",
72  "planning_scene_diff",
73  "planning_time",
74  "plan_only",
75  "start_state")
76  for arg in kwargs.keys():
77  if not arg in supported_args:
78  rospy.loginfo("moveToJointPosition: unsupported argument: %s",
79  arg)
80 
81  # Create goal
82  g = MoveGroupGoal()
83 
84  # 1. fill in workspace_parameters
85 
86  # 2. fill in start_state
87  try:
88  g.request.start_state = kwargs["start_state"]
89  except KeyError:
90  g.request.start_state.is_diff = True
91 
92  # 3. fill in goal_constraints
93  c1 = Constraints()
94  for i in range(len(joints)):
95  c1.joint_constraints.append(JointConstraint())
96  c1.joint_constraints[i].joint_name = joints[i]
97  c1.joint_constraints[i].position = positions[i]
98  c1.joint_constraints[i].tolerance_above = tolerance
99  c1.joint_constraints[i].tolerance_below = tolerance
100  c1.joint_constraints[i].weight = 1.0
101  g.request.goal_constraints.append(c1)
102 
103  # 4. fill in path constraints
104 
105  # 5. fill in trajectory constraints
106 
107  # 6. fill in planner id
108  try:
109  g.request.planner_id = kwargs["planner_id"]
110  except KeyError:
111  if self.planner_id:
112  g.request.planner_id = self.planner_id
113 
114  # 7. fill in group name
115  g.request.group_name = self._group
116 
117  # 8. fill in number of planning attempts
118  try:
119  g.request.num_planning_attempts = kwargs["num_attempts"]
120  except KeyError:
121  g.request.num_planning_attempts = 1
122 
123  # 9. fill in allowed planning time
124  try:
125  g.request.allowed_planning_time = kwargs["planning_time"]
126  except KeyError:
127  g.request.allowed_planning_time = self.planning_time
128 
129  # Fill in velocity scaling factor
130  try:
131  g.request.max_velocity_scaling_factor = kwargs["max_velocity_scaling_factor"]
132  except KeyError:
133  pass # do not fill in at all
134 
135  # 10. fill in planning options diff
136  try:
137  g.planning_options.planning_scene_diff = kwargs["planning_scene_diff"]
138  except KeyError:
139  g.planning_options.planning_scene_diff.is_diff = True
140  g.planning_options.planning_scene_diff.robot_state.is_diff = True
141 
142  # 11. fill in planning options plan only
143  try:
144  g.planning_options.plan_only = kwargs["plan_only"]
145  except KeyError:
146  g.planning_options.plan_only = self.plan_only
147 
148  # 12. fill in other planning options
149  g.planning_options.look_around = False
150  g.planning_options.replan = False
151 
152  # 13. send goal
153  self._action.send_goal(g)
154  if wait:
155  self._action.wait_for_result()
156  return self._action.get_result()
157  else:
158  return None
159 
160  ## @brief Move the arm, based on a goal pose_stamped for the end effector.
161  def moveToPose(self,
162  pose_stamped,
163  gripper_frame,
164  tolerance=0.01,
165  wait=True,
166  **kwargs):
167  # Check arguments
168  supported_args = ("max_velocity_scaling_factor",
169  "planner_id",
170  "planning_time",
171  "plan_only",
172  "start_state")
173  for arg in kwargs.keys():
174  if not arg in supported_args:
175  rospy.loginfo("moveToPose: unsupported argument: %s",
176  arg)
177 
178  # Create goal
179  g = MoveGroupGoal()
180  pose_transformed = self._listener.transformPose(self._fixed_frame, pose_stamped)
181 
182  # 1. fill in request workspace_parameters
183 
184  # 2. fill in request start_state
185  try:
186  g.request.start_state = kwargs["start_state"]
187  except KeyError:
188  g.request.start_state.is_diff = True
189 
190  # 3. fill in request goal_constraints
191  c1 = Constraints()
192 
193  c1.position_constraints.append(PositionConstraint())
194  c1.position_constraints[0].header.frame_id = self._fixed_frame
195  c1.position_constraints[0].link_name = gripper_frame
196  b = BoundingVolume()
197  s = SolidPrimitive()
198  s.dimensions = [tolerance * tolerance]
199  s.type = s.SPHERE
200  b.primitives.append(s)
201  b.primitive_poses.append(pose_transformed.pose)
202  c1.position_constraints[0].constraint_region = b
203  c1.position_constraints[0].weight = 1.0
204 
205  c1.orientation_constraints.append(OrientationConstraint())
206  c1.orientation_constraints[0].header.frame_id = self._fixed_frame
207  c1.orientation_constraints[0].orientation = pose_transformed.pose.orientation
208  c1.orientation_constraints[0].link_name = gripper_frame
209  c1.orientation_constraints[0].absolute_x_axis_tolerance = tolerance
210  c1.orientation_constraints[0].absolute_y_axis_tolerance = tolerance
211  c1.orientation_constraints[0].absolute_z_axis_tolerance = tolerance
212  c1.orientation_constraints[0].weight = 1.0
213 
214  g.request.goal_constraints.append(c1)
215 
216  # 4. fill in request path constraints
217 
218  # 5. fill in request trajectory constraints
219 
220  # 6. fill in request planner id
221  try:
222  g.request.planner_id = kwargs["planner_id"]
223  except KeyError:
224  if self.planner_id:
225  g.request.planner_id = self.planner_id
226 
227  # 7. fill in request group name
228  g.request.group_name = self._group
229 
230  # 8. fill in request number of planning attempts
231  try:
232  g.request.num_planning_attempts = kwargs["num_attempts"]
233  except KeyError:
234  g.request.num_planning_attempts = 1
235 
236  # 9. fill in request allowed planning time
237  try:
238  g.request.allowed_planning_time = kwargs["planning_time"]
239  except KeyError:
240  g.request.allowed_planning_time = self.planning_time
241 
242  # Fill in velocity scaling factor
243  try:
244  g.request.max_velocity_scaling_factor = kwargs["max_velocity_scaling_factor"]
245  except KeyError:
246  pass # do not fill in at all
247 
248  # 10. fill in planning options diff
249  g.planning_options.planning_scene_diff.is_diff = True
250  g.planning_options.planning_scene_diff.robot_state.is_diff = True
251 
252  # 11. fill in planning options plan only
253  try:
254  g.planning_options.plan_only = kwargs["plan_only"]
255  except KeyError:
256  g.planning_options.plan_only = self.plan_only
257 
258  # 12. fill in other planning options
259  g.planning_options.look_around = False
260  g.planning_options.replan = False
261 
262  # 13. send goal
263  self._action.send_goal(g)
264  if wait:
265  self._action.wait_for_result()
266  return self._action.get_result()
267  else:
268  return None
269 
270  ## @brief Sets the planner_id used for all future planning requests.
271  ## @param planner_id The string for the planner id, set to None to clear
272  def setPlannerId(self, planner_id):
273  self.planner_id = str(planner_id)
274 
275  ## @brief Set default planning time to be used for future planning request.
276  def setPlanningTime(self, time):
277  self.planning_time = time
def __init__(self, group, frame, listener=None, plan_only=False)
Constructor for this utility.
def setPlanningTime(self, time)
Set default planning time to be used for future planning request.
def moveToPose(self, pose_stamped, gripper_frame, tolerance=0.01, wait=True, kwargs)
Move the arm, based on a goal pose_stamped for the end effector.
def setPlannerId(self, planner_id)
Sets the planner_id used for all future planning requests.
def moveToJointPosition(self, joints, positions, tolerance=0.01, wait=True, kwargs)
Move the arm to set of joint position goals.
Pure python interface to move_group action.


moveit_python
Author(s): Michael Ferguson
autogenerated on Wed Jun 5 2019 21:51:17