3 PKG =
"pr2_mechanism_controllers"
5 import roslib; roslib.load_manifest(PKG)
12 from std_msgs
import *
14 from pr2_msgs.msg
import PeriodicCmd
15 from time
import sleep
19 send_periodic_cmd.py [controller] [profile] [period] [amplitude] [offset]
20 - [profile] - Possible options are linear or linear_blended
21 - [period] - Time for one entire cycle to execute (in seconds)
22 - [amplitude] - Distance max value to min value of profile (In radians for laser_tilt controller)
23 - [offset] - Constant cmd to add to profile (offset=0 results in profile centered around 0)
27 if __name__ ==
'__main__':
28 rospy.init_node(
'periodic_cmd_commander', sys.argv, anonymous=
True)
30 if len(sys.argv) != 6:
34 controller = sys.argv[1]
35 cmd.header = rospy.Header(
None,
None,
None)
36 cmd.profile = sys.argv[2]
37 cmd.period = float (sys.argv[3])
38 cmd.amplitude = float (sys.argv[4])
39 cmd.offset = float (sys.argv[5])
41 print(
'Sending Command to %s: ' % controller)
42 print(
' Profile Type: %s' % cmd.profile)
43 print(
' Period: %f Seconds' % cmd.period)
44 print(
' Amplitude: %f Radians' % cmd.amplitude)
45 print(
' Offset: %f Radians' % cmd.offset)
47 command_publisher = rospy.Publisher(controller +
'/set_periodic_cmd', PeriodicCmd)
49 command_publisher.publish( cmd )
53 print(
'Command sent!')