5 from sensor_msgs.msg
import JoyFeedbackArray
6 from sensor_msgs.msg
import JoyFeedback
8 roslib.load_manifest(
'wiimote')
10 INTER_PATTERN_SLEEP_DURATION = 0.2
14 pub = rospy.Publisher(
'/joy/set_feedback', JoyFeedbackArray, queue_size=1)
15 rospy.init_node(
'ledControlTester', anonymous=
True)
18 led0.type = JoyFeedback.TYPE_LED
21 led1.type = JoyFeedback.TYPE_LED
24 led2.type = JoyFeedback.TYPE_LED
27 led3.type = JoyFeedback.TYPE_LED
30 rum.type = JoyFeedback.TYPE_RUMBLE
33 while not rospy.is_shutdown():
34 msg = JoyFeedbackArray()
35 msg.array = [led0, led1, led2, led3, rum]
42 rospy.logdebug(
"Msg: " + str(msg))
44 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
50 rospy.logdebug(
"Msg: " + str(msg))
52 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
59 rospy.logdebug(
"Msg: " + str(msg))
61 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
68 rospy.logdebug(
"Msg: " + str(msg))
70 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
77 rospy.logdebug(
"Msg: " + str(msg))
79 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
86 rospy.logdebug(
"Msg: " + str(msg))
88 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
94 msg.array = [led0, led1, led2]
97 rospy.logdebug(
"Msg: " + str(msg))
99 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
102 if __name__ ==
'__main__':
104 print(
"\n ****************************************************************\n")
105 print(
"**** You should see six LED on/off configurations, and feel Rumbles! ****")
106 print(
"\n **************************************************************")
107 print(
"[off, off, off, off]")
108 print(
"[on, off, off, off]")
109 print(
"[off, on, off, off]")
110 print(
"[off, off, on, off]")
111 print(
"[off, off, off, on ]")
112 print(
"[off, on, on, on ]")
113 print(
"[on, off, off, on ]")
116 except rospy.ROSInterruptException: