3 import roslib; roslib.load_manifest(
'wiimote')
5 from sensor_msgs.msg
import JoyFeedbackArray
6 from sensor_msgs.msg
import JoyFeedback
12 INTER_PATTERN_SLEEP_DURATION = 0.2
15 pub = rospy.Publisher(
'/joy/set_feedback', JoyFeedbackArray, queue_size=1)
16 rospy.init_node(
'ledControlTester', anonymous=
True)
19 led0.type = JoyFeedback.TYPE_LED
22 led1.type = JoyFeedback.TYPE_LED
25 led2.type = JoyFeedback.TYPE_LED
28 led3.type = JoyFeedback.TYPE_LED
31 rum.type = JoyFeedback.TYPE_RUMBLE
35 while not rospy.is_shutdown():
37 msg = JoyFeedbackArray()
38 msg.array = [led0, led1, led2, led3, rum]
45 rospy.logdebug(
"Msg: " + str(msg))
47 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
53 rospy.logdebug(
"Msg: " + str(msg))
55 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
62 rospy.logdebug(
"Msg: " + str(msg))
64 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
71 rospy.logdebug(
"Msg: " + str(msg))
73 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
80 rospy.logdebug(
"Msg: " + str(msg))
82 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
89 rospy.logdebug(
"Msg: " + str(msg))
91 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
97 msg.array = [led0, led1, led2]
100 rospy.logdebug(
"Msg: " + str(msg))
102 rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
105 if __name__ ==
'__main__':
107 print(
"\n ****************************************************************\n")
108 print(
"**** You should see six LED on/off configurations, and feel Rumbles! ****")
109 print(
"\n **************************************************************")
110 print(
"[off, off, off, off]")
111 print(
"[on, off, off, off]")
112 print(
"[off, on, off, off]")
113 print(
"[off, off, on, off]")
114 print(
"[off, off, off, on ]")
115 print(
"[off, on, on, on ]")
116 print(
"[on, off, off, on ]")
119 except rospy.ROSInterruptException: