feedbackTester.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import roslib
4 import rospy
5 from sensor_msgs.msg import JoyFeedbackArray
6 from sensor_msgs.msg import JoyFeedback
7 
8 roslib.load_manifest('wiimote')
9 
10 INTER_PATTERN_SLEEP_DURATION = 0.2
11 
12 
13 def talker():
14  pub = rospy.Publisher('/joy/set_feedback', JoyFeedbackArray, queue_size=1)
15  rospy.init_node('ledControlTester', anonymous=True)
16 
17  led0 = JoyFeedback()
18  led0.type = JoyFeedback.TYPE_LED
19  led0.id = 0
20  led1 = JoyFeedback()
21  led1.type = JoyFeedback.TYPE_LED
22  led1.id = 1
23  led2 = JoyFeedback()
24  led2.type = JoyFeedback.TYPE_LED
25  led2.id = 2
26  led3 = JoyFeedback()
27  led3.type = JoyFeedback.TYPE_LED
28  led3.id = 3
29  rum = JoyFeedback()
30  rum.type = JoyFeedback.TYPE_RUMBLE
31  rum.id = 0
32 
33  while not rospy.is_shutdown():
34  msg = JoyFeedbackArray()
35  msg.array = [led0, led1, led2, led3, rum]
36 
37  led0.intensity = 0.2
38  led3.intensity = 0.2
39  rum.intensity = 0.49
40 
41  if msg is not None:
42  rospy.logdebug("Msg: " + str(msg))
43  pub.publish(msg)
44  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
45 
46  led0.intensity = 1.0
47  rum.intensity = 0.51
48 
49  if msg is not None:
50  rospy.logdebug("Msg: " + str(msg))
51  pub.publish(msg)
52  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
53 
54  led0.intensity = 0.0
55  led1.intensity = 1.0
56  rum.intensity = 0.0
57 
58  if msg is not None:
59  rospy.logdebug("Msg: " + str(msg))
60  pub.publish(msg)
61  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
62 
63  led1.intensity = 0.0
64  led2.intensity = 1.0
65  rum.intensity = 0.7
66 
67  if msg is not None:
68  rospy.logdebug("Msg: " + str(msg))
69  pub.publish(msg)
70  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
71 
72  led2.intensity = 0.0
73  led3.intensity = 1.0
74  rum.intensity = 0.49
75 
76  if msg is not None:
77  rospy.logdebug("Msg: " + str(msg))
78  pub.publish(msg)
79  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
80 
81  led1.intensity = 1.0
82  led2.intensity = 1.0
83  rum.intensity = 1.0
84 
85  if msg is not None:
86  rospy.logdebug("Msg: " + str(msg))
87  pub.publish(msg)
88  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
89 
90  led0.intensity = 1.0
91  led1.intensity = 0.4
92  led2.intensity = 0.4
93 
94  msg.array = [led0, led1, led2]
95 
96  if msg is not None:
97  rospy.logdebug("Msg: " + str(msg))
98  pub.publish(msg)
99  rospy.sleep(INTER_PATTERN_SLEEP_DURATION)
100 
101 
102 if __name__ == '__main__':
103 
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 ]")
114  try:
115  talker()
116  except rospy.ROSInterruptException:
117  pass
feedbackTester.talker
def talker()
Definition: feedbackTester.py:13


wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Thu Dec 5 2024 03:18:13