$search
00001 #!/usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('wiimote') 00004 import rospy 00005 from wiimote.msg import LEDControl 00006 from wiimote.msg import TimedSwitch 00007 from wiimote.msg import State 00008 00009 00010 # Test the wiimote package LED control. Expect the following LED 00011 # patterns of INTER_PATTERN_SLEEP_DURATION seconds duration each: 00012 00013 00014 INTER_PATTERN_SLEEP_DURATION = 2.0 00015 00016 # 1 0 0 0 00017 # 0 1 0 0 00018 # 0 0 1 0 00019 # 0 0 0 1 00020 # 0 1 1 1 00021 # 1 0 0 1 00022 # All LEDs together blinking Morse code L: .-.. twice. 00023 00024 00025 def talker(): 00026 00027 # Send one message, or keep repeating? 00028 oneShot = False 00029 00030 morseDi = 0.2 00031 morsePause = 0.1 00032 morseDa = 0.6 00033 morseLongPause = 1.0 00034 00035 pub = rospy.Publisher('/wiimote/leds', LEDControl) 00036 rospy.init_node('ledControlTester', anonymous=True) 00037 00038 onSwitch = TimedSwitch(switch_mode=TimedSwitch.ON) 00039 offSwitch = TimedSwitch(switch_mode=TimedSwitch.OFF) 00040 noChangeSwitch = TimedSwitch(switch_mode=TimedSwitch.NO_CHANGE) 00041 00042 msg0 = LEDControl(timed_switch_array=[offSwitch, offSwitch, offSwitch, offSwitch]) 00043 msg1 = LEDControl(timed_switch_array=[onSwitch, offSwitch, offSwitch, offSwitch]) 00044 msg2 = LEDControl(timed_switch_array=[offSwitch, onSwitch, offSwitch, offSwitch]) 00045 msg3 = LEDControl(timed_switch_array=[offSwitch, offSwitch, onSwitch, offSwitch]) 00046 msg4 = LEDControl(timed_switch_array=[offSwitch, offSwitch, offSwitch, onSwitch]) 00047 msg5 = LEDControl(timed_switch_array=[offSwitch, onSwitch, onSwitch, onSwitch]) 00048 msg6 = LEDControl(timed_switch_array=[onSwitch, offSwitch, offSwitch, noChangeSwitch]) 00049 00050 00051 msg7 = LEDControl( 00052 timed_switch_array=[TimedSwitch(switch_mode=TimedSwitch.REPEAT, 00053 num_cycles = 2, 00054 pulse_pattern=[morseDi, 00055 morsePause, 00056 morseDa, 00057 morsePause, 00058 morseDi, 00059 morsePause, 00060 morseDi, 00061 morseLongPause]), 00062 TimedSwitch(switch_mode=TimedSwitch.REPEAT, 00063 num_cycles = 2, 00064 pulse_pattern=[morseDi, 00065 morsePause, 00066 morseDa, 00067 morsePause, 00068 morseDi, 00069 morsePause, 00070 morseDi, 00071 morseLongPause]), 00072 TimedSwitch(switch_mode=TimedSwitch.REPEAT, 00073 num_cycles = 2, 00074 pulse_pattern=[morseDi, 00075 morsePause, 00076 morseDa, 00077 morsePause, 00078 morseDi, 00079 morsePause, 00080 morseDi, 00081 morseLongPause]), 00082 TimedSwitch(switch_mode=TimedSwitch.REPEAT, 00083 num_cycles = 2, 00084 pulse_pattern=[morseDi, 00085 morsePause, 00086 morseDa, 00087 morsePause, 00088 morseDi, 00089 morsePause, 00090 morseDi, 00091 morseLongPause])]) 00092 00093 00094 while not rospy.is_shutdown(): 00095 00096 if msg0 is not None: 00097 rospy.logdebug("Msg0: " + str(msg0)) 00098 pub.publish(msg0) 00099 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00100 00101 if msg1 is not None: 00102 rospy.logdebug("Msg1: " + str(msg1)) 00103 pub.publish(msg1) 00104 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00105 00106 if msg2 is not None: 00107 rospy.logdebug("Msg2: " + str(msg2)) 00108 pub.publish(msg2) 00109 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00110 00111 if msg3 is not None: 00112 rospy.logdebug("Msg3: " + str(msg3)) 00113 pub.publish(msg3) 00114 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00115 00116 if msg4 is not None: 00117 rospy.logdebug("Msg4: " + str(msg4)) 00118 pub.publish(msg4) 00119 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00120 00121 if msg5 is not None: 00122 rospy.logdebug("Msg5: " + str(msg5)) 00123 pub.publish(msg5) 00124 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00125 00126 if msg6 is not None: 00127 rospy.logdebug("Msg6: " + str(msg6)) 00128 pub.publish(msg6) 00129 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00130 00131 if msg7 is not None: 00132 rospy.logdebug("Msg7: " + str(msg7)) 00133 pub.publish(msg7) 00134 rospy.sleep(INTER_PATTERN_SLEEP_DURATION) 00135 00136 00137 if __name__ == '__main__': 00138 00139 print("\n ****************************************************************\n") 00140 print("**** You should see seven LED on/off configurations, ****") 00141 print(" plus a twice-repeated, all-ligths Morse code 'L' (.-..)") 00142 print("\n **************************************************************") 00143 print("[off, off, off, off]") 00144 print("[on, off, off, off]") 00145 print("[off, on, off, off]") 00146 print("[off, off, on, off]") 00147 print("[off, off, off, on ]") 00148 print("[off, on, on, on ]") 00149 print("[on, off, off, on ]") 00150 print("Twice all LEDs flashing a Morse 'L': .-..\n") 00151 try: 00152 talker() 00153 except rospy.ROSInterruptException: 00154 pass