30 from tf.listener
import TransformListener
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
45 def __init__(self, group, frame, listener=None, plan_only=False):
50 self._action.wait_for_server()
70 supported_args = (
"max_velocity_scaling_factor",
72 "planning_scene_diff",
76 for arg
in kwargs.keys():
77 if not arg
in supported_args:
78 rospy.loginfo(
"moveToJointPosition: unsupported argument: %s",
88 g.request.start_state = kwargs[
"start_state"]
90 g.request.start_state.is_diff =
True 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)
109 g.request.planner_id = kwargs[
"planner_id"]
115 g.request.group_name = self.
_group 119 g.request.num_planning_attempts = kwargs[
"num_attempts"]
121 g.request.num_planning_attempts = 1
125 g.request.allowed_planning_time = kwargs[
"planning_time"]
131 g.request.max_velocity_scaling_factor = kwargs[
"max_velocity_scaling_factor"]
137 g.planning_options.planning_scene_diff = kwargs[
"planning_scene_diff"]
139 g.planning_options.planning_scene_diff.is_diff =
True 140 g.planning_options.planning_scene_diff.robot_state.is_diff =
True 144 g.planning_options.plan_only = kwargs[
"plan_only"]
146 g.planning_options.plan_only = self.
plan_only 149 g.planning_options.look_around =
False 150 g.planning_options.replan =
False 153 self._action.send_goal(g)
155 self._action.wait_for_result()
156 return self._action.get_result()
168 supported_args = (
"max_velocity_scaling_factor",
173 for arg
in kwargs.keys():
174 if not arg
in supported_args:
175 rospy.loginfo(
"moveToPose: unsupported argument: %s",
180 pose_transformed = self._listener.transformPose(self.
_fixed_frame, pose_stamped)
186 g.request.start_state = kwargs[
"start_state"]
188 g.request.start_state.is_diff =
True 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
198 s.dimensions = [tolerance * tolerance]
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
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
214 g.request.goal_constraints.append(c1)
222 g.request.planner_id = kwargs[
"planner_id"]
228 g.request.group_name = self.
_group 232 g.request.num_planning_attempts = kwargs[
"num_attempts"]
234 g.request.num_planning_attempts = 1
238 g.request.allowed_planning_time = kwargs[
"planning_time"]
244 g.request.max_velocity_scaling_factor = kwargs[
"max_velocity_scaling_factor"]
249 g.planning_options.planning_scene_diff.is_diff =
True 250 g.planning_options.planning_scene_diff.robot_state.is_diff =
True 254 g.planning_options.plan_only = kwargs[
"plan_only"]
256 g.planning_options.plan_only = self.
plan_only 259 g.planning_options.look_around =
False 260 g.planning_options.replan =
False 263 self._action.send_goal(g)
265 self._action.wait_for_result()
266 return self._action.get_result()
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 get_move_action(self)
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.