send_laser_traj_cmd_ms2.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 PKG = "pr2_mechanism_controllers"
4 
5 import roslib; roslib.load_manifest(PKG)
6 
7 import sys
8 import os
9 import string
10 
11 import rospy
12 from std_msgs import *
13 
14 from pr2_msgs.msg import LaserTrajCmd
15 from pr2_msgs.srv import *
16 from time import sleep
17 
18 def print_usage(exit_code = 0):
19  print '''Usage:
20  send_periodic_cmd.py [controller]
21 '''
22  sys.exit(exit_code)
23 
24 if __name__ == '__main__':
25  if len(sys.argv) < 2:
26  print_usage()
27 
28  cmd = LaserTrajCmd()
29  controller = sys.argv[1]
30  cmd.header = rospy.Header(None, None, None)
31  cmd.profile = "blended_linear"
32  #cmd.pos = [1.0, .26, -.26, -.7, -.7, -.26, .26, 1.0, 1.0]
33  d = .025
34  #cmd.time = [0.0, 0.4, 1.0, 1.1, 1.1+d, 1.2+d, 1.8+d, 2.2+d, 2.2+2*d]
35 
36  cmd.position = [1.2, -.7, 1.2]
37  cmd.time_from_start = [0.0, 1.8, 2.025]
38  cmd.time_from_start = [rospy.Duration.from_sec(x) for x in cmd.time_from_start]
39 
40  cmd.max_velocity = 5
41  cmd.max_acceleration = 5
42 
43  print 'Sending Command to %s: ' % controller
44  print ' Profile Type: %s' % cmd.profile
45  print ' Pos: %s ' % ','.join(['%.3f' % x for x in cmd.position])
46  print ' Time: %s' % ','.join(['%.3f' % x.to_sec() for x in cmd.time_from_start])
47  print ' MaxVelocity: %f' % cmd.max_velocity
48  print ' MaxAcceleration: %f' % cmd.max_acceleration
49 
50  rospy.wait_for_service(controller + '/set_traj_cmd')
51  s = rospy.ServiceProxy(controller + '/set_traj_cmd', SetLaserTrajCmd)
52  resp = s.call(SetLaserTrajCmdRequest(cmd))
53 
54  print 'Command sent!'
55  print ' Resposne: %f' % resp.start_time.to_seconds()


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Mon Jun 10 2019 14:26:33