6 from actionlib
import SimpleActionClient
7 import moveit_commander
20 self.
_move_client_move_client = SimpleActionClient(
"move_group", MoveGroupAction)
23 moveit_commander.roscpp_initialize(sys.argv)
28 self.
_goal_goal = MoveGroupGoal()
29 self.
_goal_goal.request.group_name = group_name
30 self.
_goal_goal.request.max_velocity_scaling_factor = 0.1
31 self.
_goal_goal.request.max_acceleration_scaling_factor = 0.1
32 self.
_goal_goal.request.start_state.is_diff =
True
34 goal_constraint = Constraints()
35 joint_values = [0.1, 0.2, 0.3, 0.4, 0.5, 0.6]
36 joint_names = group.get_active_joints()
37 for i
in range(len(joint_names)):
38 joint_constraint = JointConstraint()
39 joint_constraint.joint_name = joint_names[i]
40 joint_constraint.position = joint_values[i]
41 joint_constraint.weight = 1.0
42 goal_constraint.joint_constraints.append(joint_constraint)
44 self.
_goal_goal.request.goal_constraints.append(goal_constraint)
45 self.
_goal_goal.planning_options.planning_scene_diff.robot_state.is_diff =
True
66 result.error_code.val == MoveItErrorCodes.PREEMPTED
67 or result.error_code.val == 0
72 self.
_goal_goal.planning_options.plan_only =
True
92 result.error_code.val == MoveItErrorCodes.PREEMPTED
93 or result.error_code.val == 0
111 while result
is None:
116 self.assertEqual(result.error_code.val, MoveItErrorCodes.SUCCESS)
119 if __name__ ==
"__main__":
122 rospy.init_node(
"cancel_before_plan_execution")
124 "moveit_ros_move_group",
125 "test_cancel_before_plan_execution",
126 TestMoveActionCancelDrop,
def test_cancel_drop_plan_execution(self)
def test_cancel_resend(self)
def test_cancel_drop_plan_only(self)