Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import roslib; roslib.load_manifest('kobuki_testsuite')
00036 import rospy
00037
00038 from kobuki_msgs.msg import DigitalOutput
00039
00040 rospy.init_node("test_digital_output")
00041 pub = rospy.Publisher('/mobile_base/commands/digital_output',DigitalOutput)
00042 rate = rospy.Rate(1)
00043 digital_output = DigitalOutput()
00044 digital_output.values = [ False, False, False, False]
00045 digital_output.mask = [ True, True, False, True ]
00046 print ""
00047 print "This program will start sending a variety of digital io signals to the robot."
00048 print "It will set all output signals to false, then iteratively turn each one to True"
00049 print "In doing so, it will cycle through a mask that will negate the setting for one"
00050 print "of the outputs. The process then repeats itself masking the next output in the"
00051 print "sequence instead."
00052 print ""
00053 while not rospy.is_shutdown():
00054
00055 try:
00056 index = digital_output.values.index(False)
00057 for i in range(0,4):
00058 if not digital_output.values[i]:
00059 digital_output.values[i] = True
00060 break
00061 except ValueError:
00062 digital_output.values = [ False, False, False, False]
00063 index = digital_output.mask.index(False)
00064 digital_output.mask[index] = True
00065 if index == 3:
00066 next_index = 0
00067 else:
00068 next_index = index + 1
00069 digital_output.mask[next_index] = False
00070 print digital_output
00071 pub.publish(digital_output)
00072 rate.sleep()
00073