Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 import rospy
00029 import actionlib
00030 from tf.listener import TransformListener
00031 from geometry_msgs.msg import *
00032 from moveit_msgs.msg import MoveGroupAction, MoveGroupGoal
00033 from moveit_msgs.msg import Constraints, JointConstraint, PositionConstraint, OrientationConstraint, BoundingVolume
00034 from shape_msgs.msg import SolidPrimitive
00035
00036
00037
00038 class MoveGroupInterface(object):
00039
00040
00041
00042
00043
00044
00045 def __init__(self, group, frame, listener=None, plan_only=False):
00046 self._group = group
00047 self._fixed_frame = frame
00048 self._action = actionlib.SimpleActionClient('move_group',
00049 MoveGroupAction)
00050 self._action.wait_for_server()
00051 if listener == None:
00052 self._listener = TransformListener()
00053 else:
00054 self._listener = listener
00055 self.plan_only = plan_only
00056 self.planner_id = None
00057 self.planning_time = 15.0
00058
00059 def get_move_action(self):
00060 return self._action
00061
00062
00063 def moveToJointPosition(self,
00064 joints,
00065 positions,
00066 tolerance=0.01,
00067 wait=True,
00068 **kwargs):
00069
00070 supported_args = ("max_velocity_scaling_factor",
00071 "planner_id",
00072 "planning_scene_diff",
00073 "planning_time",
00074 "plan_only",
00075 "start_state")
00076 for arg in kwargs.keys():
00077 if not arg in supported_args:
00078 rospy.loginfo("moveToJointPosition: unsupported argument: %s",
00079 arg)
00080
00081
00082 g = MoveGroupGoal()
00083
00084
00085
00086
00087 try:
00088 g.request.start_state = kwargs["start_state"]
00089 except KeyError:
00090 g.request.start_state.is_diff = True
00091
00092
00093 c1 = Constraints()
00094 for i in range(len(joints)):
00095 c1.joint_constraints.append(JointConstraint())
00096 c1.joint_constraints[i].joint_name = joints[i]
00097 c1.joint_constraints[i].position = positions[i]
00098 c1.joint_constraints[i].tolerance_above = tolerance
00099 c1.joint_constraints[i].tolerance_below = tolerance
00100 c1.joint_constraints[i].weight = 1.0
00101 g.request.goal_constraints.append(c1)
00102
00103
00104
00105
00106
00107
00108 try:
00109 g.request.planner_id = kwargs["planner_id"]
00110 except KeyError:
00111 if self.planner_id:
00112 g.request.planner_id = self.planner_id
00113
00114
00115 g.request.group_name = self._group
00116
00117
00118 try:
00119 g.request.num_planning_attempts = kwargs["num_attempts"]
00120 except KeyError:
00121 g.request.num_planning_attempts = 1
00122
00123
00124 try:
00125 g.request.allowed_planning_time = kwargs["planning_time"]
00126 except KeyError:
00127 g.request.allowed_planning_time = self.planning_time
00128
00129
00130 try:
00131 g.request.max_velocity_scaling_factor = kwargs["max_velocity_scaling_factor"]
00132 except KeyError:
00133 pass
00134
00135
00136 try:
00137 g.planning_options.planning_scene_diff = kwargs["planning_scene_diff"]
00138 except KeyError:
00139 g.planning_options.planning_scene_diff.is_diff = True
00140 g.planning_options.planning_scene_diff.robot_state.is_diff = True
00141
00142
00143 try:
00144 g.planning_options.plan_only = kwargs["plan_only"]
00145 except KeyError:
00146 g.planning_options.plan_only = self.plan_only
00147
00148
00149 g.planning_options.look_around = False
00150 g.planning_options.replan = False
00151
00152
00153 self._action.send_goal(g)
00154 if wait:
00155 self._action.wait_for_result()
00156 return self._action.get_result()
00157 else:
00158 return None
00159
00160
00161 def moveToPose(self,
00162 pose_stamped,
00163 gripper_frame,
00164 tolerance=0.01,
00165 wait=True,
00166 **kwargs):
00167
00168 supported_args = ("max_velocity_scaling_factor",
00169 "planner_id",
00170 "planning_time",
00171 "plan_only",
00172 "start_state")
00173 for arg in kwargs.keys():
00174 if not arg in supported_args:
00175 rospy.loginfo("moveToJointPosition: unsupported argument: %s",
00176 arg)
00177
00178
00179 g = MoveGroupGoal()
00180 pose_transformed = self._listener.transformPose(self._fixed_frame, pose_stamped)
00181
00182
00183
00184
00185 try:
00186 g.request.start_state = kwargs["start_state"]
00187 except KeyError:
00188 g.request.start_state.is_diff = True
00189
00190
00191 c1 = Constraints()
00192
00193 c1.position_constraints.append(PositionConstraint())
00194 c1.position_constraints[0].header.frame_id = self._fixed_frame
00195 c1.position_constraints[0].link_name = gripper_frame
00196 b = BoundingVolume()
00197 s = SolidPrimitive()
00198 s.dimensions = [tolerance * tolerance]
00199 s.type = s.SPHERE
00200 b.primitives.append(s)
00201 b.primitive_poses.append(pose_transformed.pose)
00202 c1.position_constraints[0].constraint_region = b
00203 c1.position_constraints[0].weight = 1.0
00204
00205 c1.orientation_constraints.append(OrientationConstraint())
00206 c1.orientation_constraints[0].header.frame_id = self._fixed_frame
00207 c1.orientation_constraints[0].orientation = pose_transformed.pose.orientation
00208 c1.orientation_constraints[0].link_name = gripper_frame
00209 c1.orientation_constraints[0].absolute_x_axis_tolerance = tolerance
00210 c1.orientation_constraints[0].absolute_y_axis_tolerance = tolerance
00211 c1.orientation_constraints[0].absolute_z_axis_tolerance = tolerance
00212 c1.orientation_constraints[0].weight = 1.0
00213
00214 g.request.goal_constraints.append(c1)
00215
00216
00217
00218
00219
00220
00221 try:
00222 g.request.planner_id = kwargs["planner_id"]
00223 except KeyError:
00224 if self.planner_id:
00225 g.request.planner_id = self.planner_id
00226
00227
00228 g.request.group_name = self._group
00229
00230
00231 try:
00232 g.request.num_planning_attempts = kwargs["num_attempts"]
00233 except KeyError:
00234 g.request.num_planning_attempts = 1
00235
00236
00237 try:
00238 g.request.allowed_planning_time = kwargs["planning_time"]
00239 except KeyError:
00240 g.request.allowed_planning_time = self.planning_time
00241
00242
00243 try:
00244 g.request.max_velocity_scaling_factor = kwargs["max_velocity_scaling_factor"]
00245 except KeyError:
00246 pass
00247
00248
00249 g.planning_options.planning_scene_diff.is_diff = True
00250 g.planning_options.planning_scene_diff.robot_state.is_diff = True
00251
00252
00253 try:
00254 g.planning_options.plan_only = kwargs["plan_only"]
00255 except KeyError:
00256 g.planning_options.plan_only = self.plan_only
00257
00258
00259 g.planning_options.look_around = False
00260 g.planning_options.replan = False
00261
00262
00263 self._action.send_goal(g)
00264 if wait:
00265 self._action.wait_for_result()
00266 return self._action.get_result()
00267 else:
00268 return None
00269
00270
00271
00272 def setPlannerId(self, planner_id):
00273 self.planner_id = str(planner_id)
00274
00275
00276 def setPlanningTime(self, time):
00277 self.planning_time = time