2 from __future__
import print_function
4 import roslib; roslib.load_manifest(
'ur_driver')
10 JOINT_NAMES = [
'shoulder_pan_joint',
'shoulder_lift_joint',
'elbow_joint',
11 'wrist_1_joint',
'wrist_2_joint',
'wrist_3_joint']
12 Q1 = [2.2,0,-1.57,0,0,0]
13 Q2 = [1.5,0,-1.57,0,0,0]
14 Q3 = [1.5,-0.2,-1.57,0,0,0]
19 g = FollowJointTrajectoryGoal()
20 g.trajectory = JointTrajectory()
21 g.trajectory.joint_names = JOINT_NAMES
22 g.trajectory.points = [
23 JointTrajectoryPoint(positions=Q1, velocities=[0]*6, time_from_start=rospy.Duration(2.0)),
24 JointTrajectoryPoint(positions=Q2, velocities=[0]*6, time_from_start=rospy.Duration(3.0)),
25 JointTrajectoryPoint(positions=Q3, velocities=[0]*6, time_from_start=rospy.Duration(4.0))]
28 client.wait_for_result()
29 except KeyboardInterrupt:
34 order = [4, 2, 3, 1, 5, 0]
35 g = FollowJointTrajectoryGoal()
36 g.trajectory = JointTrajectory()
37 g.trajectory.joint_names = [JOINT_NAMES[i]
for i
in order]
38 q1 = [Q1[i]
for i
in order]
39 q2 = [Q2[i]
for i
in order]
40 q3 = [Q3[i]
for i
in order]
41 g.trajectory.points = [
42 JointTrajectoryPoint(positions=q1, velocities=[0]*6, time_from_start=rospy.Duration(2.0)),
43 JointTrajectoryPoint(positions=q2, velocities=[0]*6, time_from_start=rospy.Duration(3.0)),
44 JointTrajectoryPoint(positions=q3, velocities=[0]*6, time_from_start=rospy.Duration(4.0))]
46 client.wait_for_result()
49 g = FollowJointTrajectoryGoal()
50 g.trajectory = JointTrajectory()
51 g.trajectory.joint_names = JOINT_NAMES
54 g.trajectory.points = []
56 g.trajectory.points.append(
57 JointTrajectoryPoint(positions=Q1, velocities=[0]*6, time_from_start=rospy.Duration(d)))
59 g.trajectory.points.append(
60 JointTrajectoryPoint(positions=Q2, velocities=[0]*6, time_from_start=rospy.Duration(d)))
62 g.trajectory.points.append(
63 JointTrajectoryPoint(positions=Q3, velocities=[0]*6, time_from_start=rospy.Duration(d)))
67 client.wait_for_result()
68 except KeyboardInterrupt:
73 g = FollowJointTrajectoryGoal()
74 g.trajectory = JointTrajectory()
75 g.trajectory.joint_names = JOINT_NAMES
76 g.trajectory.points = [
77 JointTrajectoryPoint(positions=Q1, velocities=[0]*6, time_from_start=rospy.Duration(2.0)),
78 JointTrajectoryPoint(positions=Q2, velocities=[0]*6, time_from_start=rospy.Duration(3.0)),
79 JointTrajectoryPoint(positions=Q3, velocities=[0]*6, time_from_start=rospy.Duration(4.0))]
86 client.wait_for_result()
87 except KeyboardInterrupt:
94 rospy.init_node(
"test_move", anonymous=
True, disable_signals=
True)
96 print(
"Waiting for server...")
97 client.wait_for_server()
98 print(
"Connected to server")
103 except KeyboardInterrupt:
104 rospy.signal_shutdown(
"KeyboardInterrupt")
107 if __name__ ==
'__main__':
main()