00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 import roslib; roslib.load_manifest('wiimote')
00013 import rospy
00014 from wiimote.msg import TimedSwitch
00015 from wiimote.msg import RumbleControl
00016
00017 from wiimote.wiimoteConstants import SWITCH_ON
00018 from wiimote.wiimoteConstants import SWITCH_OFF
00019 from wiimote.wiimoteConstants import SWITCH_PULSE_PATTERN
00020
00021 morseDi = 0.2
00022 morsePause = 0.1
00023 morseDa = 0.6
00024 morseLongPause = 1.0
00025
00026 INTER_PATTERN_SLEEP_DURATION = 3.0
00027
00028 def printMsg(msg):
00029 pattern = msg.rumble.pulse_pattern
00030 print "switch_mode: %2d; num_cycles: %3d, pulse_pattern:\n[" % (msg.rumble.switch_mode, msg.rumble.num_cycles)
00031 for duration in pattern:
00032 print "%.2f, " % (duration),
00033 print "]"
00034
00035
00036
00037 def talker():
00038
00039
00040 oneShot = True
00041
00042 pub = rospy.Publisher('/wiimote/rumble', RumbleControl)
00043 rospy.init_node('rumbleTester', anonymous=True)
00044
00045
00046 sendBlank(pub)
00047 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
00048
00049
00050
00051 sendOneMorse(pub)
00052 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
00053
00054
00055
00056 sendTwoMorse(pub)
00057 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
00058
00059
00060
00061
00062 def sendBlank(pub):
00063
00064 print("Ask wiimote node for pattern, but set num_cycles=0. ==> No rumble")
00065 msg = RumbleControl(TimedSwitch(switch_mode=SWITCH_PULSE_PATTERN,
00066 num_cycles = 0,
00067 pulse_pattern=[morseDi,
00068 morsePause,
00069 morseDa,
00070 morsePause,
00071 morseDi,
00072 morsePause,
00073 morseDi,
00074 morseLongPause]))
00075
00076 printMsg(msg)
00077 pub.publish(msg)
00078
00079
00080 def sendOneMorse(pub):
00081
00082 print("Ask wiimote node for pattern, set num_cycles=1. ==> One Morse '. - . .' rumble")
00083 msg = RumbleControl(TimedSwitch(switch_mode=SWITCH_PULSE_PATTERN,
00084 num_cycles = 1,
00085 pulse_pattern=[morseDi,
00086 morsePause,
00087 morseDa,
00088 morsePause,
00089 morseDi,
00090 morsePause,
00091 morseDi,
00092 morseLongPause]))
00093
00094 printMsg(msg)
00095 pub.publish(msg)
00096
00097
00098 def sendTwoMorse(pub):
00099
00100 print("Ask wiimote node for rumble pattern, set num_cycles=2. ==> Two Morse '. - . .' rumble cycles")
00101 msg = RumbleControl(TimedSwitch(switch_mode=SWITCH_PULSE_PATTERN,
00102 num_cycles = 2,
00103 pulse_pattern=[morseDi,
00104 morsePause,
00105 morseDa,
00106 morsePause,
00107 morseDi,
00108 morsePause,
00109 morseDi,
00110 morseLongPause]))
00111
00112 printMsg(msg)
00113 pub.publish(msg)
00114
00115
00116 if __name__ == '__main__':
00117 try:
00118 print("\n ****************************************************************************************\n")
00119 print("**** You should feel three repeated vibrations, spelling out Morse code pattern for 'L': .-.. *****\n")
00120 print("Console messages below describe ROS messages being sent.")
00121 print("\n ****************************************************************************************\n\n")
00122 talker()
00123 except rospy.ROSInterruptException: pass