test_move.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 from __future__ import print_function
3 import time
4 import roslib; roslib.load_manifest('ur_driver')
5 import rospy
6 import actionlib
7 from control_msgs.msg import *
8 from trajectory_msgs.msg import *
9 
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]
15 
16 client = None
17 
18 def move1():
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))]
26  client.send_goal(g)
27  try:
28  client.wait_for_result()
29  except KeyboardInterrupt:
30  client.cancel_goal()
31  raise
32 
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))]
45  client.send_goal(g)
46  client.wait_for_result()
47 
49  g = FollowJointTrajectoryGoal()
50  g.trajectory = JointTrajectory()
51  g.trajectory.joint_names = JOINT_NAMES
52 
53  d = 2.0
54  g.trajectory.points = []
55  for i in range(10):
56  g.trajectory.points.append(
57  JointTrajectoryPoint(positions=Q1, velocities=[0]*6, time_from_start=rospy.Duration(d)))
58  d += 1
59  g.trajectory.points.append(
60  JointTrajectoryPoint(positions=Q2, velocities=[0]*6, time_from_start=rospy.Duration(d)))
61  d += 1
62  g.trajectory.points.append(
63  JointTrajectoryPoint(positions=Q3, velocities=[0]*6, time_from_start=rospy.Duration(d)))
64  d += 2
65  client.send_goal(g)
66  try:
67  client.wait_for_result()
68  except KeyboardInterrupt:
69  client.cancel_goal()
70  raise
71 
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))]
80 
81  client.send_goal(g)
82  time.sleep(2.0)
83  print("Interrupting")
84  client.send_goal(g)
85  try:
86  client.wait_for_result()
87  except KeyboardInterrupt:
88  client.cancel_goal()
89  raise
90 
91 def main():
92  global client
93  try:
94  rospy.init_node("test_move", anonymous=True, disable_signals=True)
95  client = actionlib.SimpleActionClient('follow_joint_trajectory', FollowJointTrajectoryAction)
96  print("Waiting for server...")
97  client.wait_for_server()
98  print("Connected to server")
99  #move1()
100  move_repeated()
101  #move_disordered()
102  #move_interrupt()
103  except KeyboardInterrupt:
104  rospy.signal_shutdown("KeyboardInterrupt")
105  raise
106 
107 if __name__ == '__main__': main()
def move1()
Definition: test_move.py:18
def move_repeated()
Definition: test_move.py:48
def move_disordered()
Definition: test_move.py:33
def main()
Definition: test_move.py:91
def move_interrupt()
Definition: test_move.py:72


ur_driver
Author(s): Stuart Glaser, Shaun Edwards, Felix Messmer
autogenerated on Sun Nov 24 2019 03:36:29