WIIMote.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # ###############################################################################
3 #
4 # File: WIIMote.py
5 # RCS: $Header: $
6 # Description: Top Level Wii Remote Control
7 # Author: Andreas Paepcke
8 # Created: Thu Aug 13 09:00:27 2009
9 # Modified: Fri Jan 14 10:48:48 2011 (Andreas Paepcke) paepcke@bhb.willowgarage.com
10 # Language: Python
11 # Package: N/A
12 # Status: Experimental (Do Not Distribute)
13 #
14 #
15 # ###############################################################################
16 #
17 # Revisions:
18 #
19 # Fri Jan 14 10:48:11 2011 (Andreas Paepcke) paepcke@bhb.willowgarage.com
20 # Added warning to ignore error messages when neither Nunchuk nor WiimotePlus
21 # are present.
22 # Thu Jan 13 17:29:06 2011 (Andreas Paepcke) paepcke@bhb.willowgarage.com
23 # Added shutdown exception guard in getRumble()
24 # Thu Sep 10 10:27:38 2009 (Andreas Paepcke) paepcke@anw.willowgarage.com
25 # Added option to lock access to wiiMoteState instance variable.
26 # Thu Mar 18 10:56:09 2010 (David Lu) davidlu@wustl.edu
27 # Enabled nunchuk reports
28 # Fri Oct 29 08:58:21 2010 (Miguel Angel Julian Aguilar, QBO Project) miguel.angel@thecorpora.com
29 # Enabled classic controller reports
30 # Mon Nov 08 11:44:39 2010 (David Lu) davidlu@wustl.edu
31 # Added nunchuk calibration
32 # ###############################################################################
33 
34 import operator
35 import time
36 import sys
37 import threading
38 from math import *
39 import tempfile
40 import os
41 
42 import rospy
43 
44 import numpy as np
45 import cwiid
46 
47 from wiiutils import *
48 from wiimoteExceptions import *
49 from wiimoteConstants import *
50 import wiistate
51 
52 
53 class WIIMote(object):
54  """
55  Main class for Wiimote device interaction.
56 
57  This class should be a singleton, or it should have
58  only class members/methods.
59 
60  Public Data attributes:
61  wiiMoteState WIIState object that holds the latest sampled state
62  sampleRate Control Wiimote state samples to take per second
63  meanAcc Triplet with mean of accelerator at rest
64  stdevAcc Triplet with standard deviation of accelerator at rest
65  meanGyro Triplet with mean of gyro (angular rate) at rest
66  stdevGyro Triplet with standard deviation gyro (angular rate) at rest
67 
68  Public Methods:
69 
70  """
71  BATTERY_MAX = cwiid.BATTERY_MAX # 208 a.k.a. 0xD0
72 
73  _wm = None # WIIMote object
74  _wiiCallbackStack = None # Stack for directing Wii driver callbacks
75 
76  _startTime = None # Used for state sampling
77  _accList = None # Collecting accelerator readings for zeroing and others
78  _gyroList = None
79  _readingsCnt = None # For counting how many readings were taken
80  _accTotal = None # Summed up acc readings in one AccReading instance
81  _gyroTotal = None # Summed up gyro readings in one AccReading instance
82 
83  _accNormal = None # Readings of accelerometer at rest
84  _gyroNormal = None # Readings of gyro at rest
85 
86  _nunchukJoyOrig = None # Initial Reading of the nunchuk's joystick
87 
88  _LEDMasksOn = [LED1_ON, LED2_ON, LED3_ON, LED4_ON] # OR to turn on
89  _LEDMasksOff = [0 | LED2_ON | LED3_ON | LED4_ON, # AND to turn off
90  0 | LED1_ON | LED3_ON | LED4_ON,
91  0 | LED1_ON | LED2_ON | LED4_ON,
92  0 | LED1_ON | LED2_ON | LED3_ON]
93 
94  def __init__(self, theSampleRate=0, wiiStateLock=None, gatherCalibrationStats=False):
95  """
96  Instantiate a Wiimote driver instance, which controls one physical Wiimote device.
97 
98  Parameters:
99  theSampleRate: How often to update the instance's wiiMoteState variable:
100  theSampleRate= -1: never
101  theSampleRate= 0: as often as possible
102  theSampleRate= x: every x seconds
103  """
104 
105  self.lastZeroingTime = 0.
106 
107  self.gatherCalibrationStats = gatherCalibrationStats
108  if (self.gatherCalibrationStats):
110  for i in range(NUM_ZEROING_READINGS):
112 
113  # Create a threading.Lock instance.
114  # The instance variable wiiMoteState is only updated after acquiring that
115  # lock. This is true for both reading and writing. The same is
116  # true for accesses to: meanAcc, stdevAcc, varAcc, stdevGyro, and varGyro
117  # All such accesses happen w/in this class, b/c we have accessors for
118  # these variables. The lock is used also in method zeroDevice() as
119  # well, to prevent other threads from retrieving bad values between
120  # the time zeroDevice() begins and ends:
121 
122  self.wiiStateLock = threading.Lock()
123  self.wiiMoteState = None # Object holding a snapshot of the Wiimote state
124  self.sampleRate = -1 # How often to update wiiMoteState
125  # -1: Never
126  # 0: Everytime the underlying system offers state
127  # else: (Possibly fractional) seconds between updates
128 
129  # Mean x/y/z of most recent accelerometer zeroing in Gs and metric:
130  self.meanAcc = np.array([None, None, None], dtype=np.float64)
131  self.meanAccMetric = np.array([None, None, None], dtype=np.float64)
132  # Stdev x/y/z of most recent accelerometer zeroing in Gs and metric:
133  self.stdevAcc = np.array([None, None, None], dtype=np.float64)
134  self.stdevAccMetric = np.array([None, None, None], dtype=np.float64)
135  # Variance x/y/z of most recent accelerometer zeroing
136  self.varAcc = np.array([None, None, None], dtype=np.float64)
137 
138  # Mean x/y/z of most recent gyro zeroing in Gs and metric:
139  self.meanGyro = np.array([None, None, None], dtype=np.float64)
140  self.meanGyroMetric = np.array([None, None, None], dtype=np.float64)
141  # Stdev x/y/z of most recent gyro zeroing in Gs and metric:
142  self.stdevGyro = np.array([None, None, None], dtype=np.float64)
143  self.stdevGyroMetric = np.array([None, None, None], dtype=np.float64)
144  # Variance x/y/z of most recent gyro zeroing
145  self.varGyroMetric = np.array([None, None, None], dtype=np.float64)
146 
148 
149  promptUsr("Press buttons 1 and 2 together to pair (within 6 seconds).\n "
150  "(If no blinking lights, press power button for ~3 seconds.)")
151 
152  try:
153  self._wm = cwiid.Wiimote()
154  except RuntimeError:
155  raise WiimoteNotFoundError("No Wiimote found to pair with.")
156  exit()
157 
158  rospy.loginfo("Pairing successful.")
159 
160  try:
161  self._wm.enable(cwiid.FLAG_MOTIONPLUS)
162  except RuntimeError:
163  raise WiimoteEnableError("Found Wiimote, but could not enable it.")
164  exit
165 
166  self.sampleRate = theSampleRate
167  self._startTime = getTimeStamp()
168 
170 
171  # Enable reports from the WII:
172  self._wm.rpt_mode = (cwiid.RPT_ACC | cwiid.RPT_MOTIONPLUS |
173  cwiid.RPT_BTN | cwiid.RPT_IR |
174  cwiid.RPT_NUNCHUK | cwiid.RPT_CLASSIC)
175 
176  # Set accelerometer calibration to factory defaults:
177  (factoryZero, factoryOne) = self.getAccFactoryCalibrationSettings()
178  self.setAccelerometerCalibration(factoryZero, factoryOne)
179 
180  # Initialize Gyro zeroing to do nothing:
181  self.setGyroCalibration([0, 0, 0])
182 
183  # Set nunchuk calibration to factory defaults.
184  if (self._wm.state['ext_type'] == cwiid.EXT_NUNCHUK):
185  try:
186  (factoryZero, factoryOne) = self.getNunchukFactoryCalibrationSettings()
187  self.setNunchukAccelerometerCalibration(factoryZero, factoryOne)
188 
189  time.sleep(0.2)
191 
192  rospy.loginfo("Wiimote activated.")
193 
194  def _steadyStateCallback(self, state, theTime):
195  now = getTimeStamp()
196  if now - self._startTime >= self.sampleRate:
197  # If this Wiimote driver is to synchronize write
198  # access to the wii state variable (which is read from
199  # outside), then acquire the lock that was provided
200  # by the instantiator of this instance:
201  if self.wiiStateLock is not None:
202  self.wiiStateLock.acquire()
203  try:
204  self.wiiMoteState = wiistate.WIIState(state, theTime, self.getRumble(), self._wm.state['buttons'])
205  except ValueError:
206  # A 'Wiimote is closed' error can occur as a race condition
207  # as threads close down after a Cnt-C. Catch those and
208  # ignore:
209  pass
210  if self.wiiStateLock is not None:
211  self.wiiStateLock.release()
212  self._startTime = now
213 
214  def _calibrationCallback(self, state, theTime):
215  """Wii's callback destination while zeroing the device."""
216 
217  self._warmupCnt += 1
218  if self._warmupCnt < NUM_WARMUP_READINGS:
219  return
220 
221  if self._readingsCnt >= NUM_ZEROING_READINGS:
222  return
223 
224  thisState = wiistate.WIIState(state, theTime, self.getRumble(), self._wm.state['buttons'])
225 
226  # Pull out the accelerometer x,y,z, accumulate in a list:
227  self._accList.append(thisState.accRaw)
228 
229  # Pull out the gyro x,y,z, and build a GyroReading from them.
230  # For a few cycles, the Wiimote does not deliver gyro info.
231  # When it doesn't, we get a 'None' is unsubscriptable. Ignore
232  # those initial instabilities:
233  try:
234  self._gyroList.append(thisState.angleRate)
235  except TypeError:
236  pass
237  self._readingsCnt += 1
238 
239  if thisState.nunchukPresent and self._nunchukJoyOrig is None:
240  self._nunchukJoyOrig = thisState.nunchukStickRaw
241  wiistate.WIIState.setNunchukJoystickCalibration(self._nunchukJoyOrig)
242 
243  return
244 
245  def zeroDevice(self):
246  """
247  Find the at-rest values of the accelerometer and the gyro.
248 
249  Collect NUM_ZEROING_READINGS readings of acc and gyro. Average them.
250  If the standard deviation of any of the six axes exceeds a threshold
251  that was determined empirically, then the calibration fails. Else
252  the gyro is biased to compensate for its at-rest offset. The offset
253  is the abs(mean(Gyro)).
254 
255  The stdev thresholds are documented in wiimoteConstants.py.
256 
257  Note that we always use the Wiimote's factory-installed zeroing data.
258  In the code below we nonetheless compute the stats for the
259  accelerometer, in case this behavior is to change in the future.
260 
261  We sleep while the samples are taken. In order to prevent other
262  threads from reading bad values for mean/stdev, and variance,
263  we lock access to those vars.
264  """
265 
266  self._accList = [] # Calibration callback will put samples here (WIIReading()s)
267  self._gyroList = [] # Calibration callback will put samples here (WIIReading()s)
268  self._readingsCnt = 0
269  self._warmupCnt = 0
270  # The factory calibration setting for the accelerometer (two values in a tuple):
271  accCalibrationOrig = self.getAccelerometerCalibration()
272  gyroCalibrationOrig = self.getGyroCalibration()
273  accArrays = [] # Place to put raw reading triplets
274  gyroArrays = [] # Place to put raw reading triplets
275 
276  try:
277  # Get the samples for accelerometer and gyro:
278  self.wiiStateLock.acquire()
279 
281 
282  # Wipe out previous calibration correction data
283  # while we gather raw samples:
284  wiistate.WIIState.setGyroCalibration([0, 0, 0])
285  wiistate.WIIState.setAccelerometerCalibration([0, 0, 0], [0, 0, 0])
286 
287  while (self._readingsCnt < NUM_ZEROING_READINGS) or (self._warmupCnt < NUM_WARMUP_READINGS):
288  time.sleep(.1)
289 
290  self._wiiCallbackStack.pause()
291  finally:
292  # Restore the callback that was in force before zeroing:
293  self._wiiCallbackStack.pop()
294  self.wiiStateLock.release()
295 
296  # Compute and store basic statistics about the readings:
297  self.computeAccStatistics()
298  self.computeGyroStatistics()
299 
300  # Extract the accelerometer reading triplets from the list of WIIReading()s:
301  for accWiiReading in self._accList:
302  if accWiiReading is not None:
303  oneAccReading = accWiiReading.tuple()
304  accArrays.append(oneAccReading)
305  accArrays = np.reshape(accArrays, (-1, 3))
306 
307  # Extract the gyro reading triplets from the list of WIIReading()s:
308  if (self.motionPlusPresent()):
309  for gyroReading in self._gyroList:
310  if (gyroReading is not None):
311  oneGyroReading = gyroReading.tuple()
312  gyroArrays.append(oneGyroReading)
313 
314  if (self.motionPlusPresent()):
315  gyroArrays = np.reshape(gyroArrays, (-1, 3))
316 
317  # We now have:
318  # [[accX1, accZ1, accZ1]
319  # [accX2, accZ2, accZ2]
320  # ...
321  # ]
322  #
323  # and:
324  #
325  # [[gyroX1, gyroZ1, gyroZ1]
326  # [gyroX2, gyroZ2, gyroZ2]
327  # ...
328  # ]
329  #
330  # Combine all into:
331  #
332  # [[accX1, accZ1, accZ1, gyroX1, gyroZ1, gyroZ1]
333  # [accX2, accZ2, accZ2, gyroX2, gyroZ2, gyroZ2]
334  # ...
335  # ]
336  #
337 
338  allData = np.append(accArrays, gyroArrays, axis=1)
339  # Will compare both, accelerometer x/y/z, and gyro x/y/z
340  # to their stdev threshold to validate calibration:
341  thresholdsArray = THRESHOLDS_ARRAY
342  else:
343  allData = accArrays
344  # Will compare only accelerometer x/y/z to their stdev
345  # threshold to validate calibration. No Wiimote+ was
346  # detected:
347  thresholdsArray = THRESHOLDS_ARRAY[0:3]
348 
349  # And take the std deviations column-wise:
350  stdev = np.std(allData, axis=0)
351 
352  # See whether any of the six stdevs exceeds the
353  # calibration threshold:
354 
355  isBadCalibration = (stdev > thresholdsArray).any()
356 
357  # We always use the factory-installed calibration info,
358  self.setAccelerometerCalibration(accCalibrationOrig[0], accCalibrationOrig[1])
359 
360  if (isBadCalibration):
361  self.latestCalibrationSuccessful = False
362  # We can calibrate the Wiimote anyway, if the preference
363  # constant in wiimoteConstants.py is set accordingly:
364  if (CALIBRATE_WITH_FAILED_CALIBRATION_DATA and self.motionPlusPresent()):
365  rospy.loginfo("Failed calibration; using questionable calibration anyway.")
366  wiistate.WIIState.setGyroCalibration(self.meanGyro)
367  else:
368  if (gyroCalibrationOrig is not None):
369  rospy.loginfo("Failed calibration; retaining previous calibration.")
370  if (self.motionPlusPresent()):
371  wiistate.WIIState.setGyroCalibration(gyroCalibrationOrig)
372  else:
373  rospy.loginfo("Failed calibration; running without calibration now.")
374  return False
375 
376  # Do WIIState's gyro zero reading, so that future
377  # readings can be corrected when a WIIState is created:
378  wiistate.WIIState.setGyroCalibration(self.meanGyro)
379 
381  rospy.loginfo("Calibration successful.")
382  self.latestCalibrationSuccessful = True
383  return True
384 
385  def getWiimoteState(self):
386  """Returns the most recent Wiistate instance. Provides proper locking."""
387 
388  return self._getInstanceVarCriticalSection("wiimoteState")
389 
391  """Accessor that provides locking."""
392 
393  return self._getInstanceVarCriticalSection("meanAcc")
394 
396  """Accessor that provides locking."""
397 
398  return self._getInstanceVarCriticalSection("stdevAcc")
399 
401  """Accessor that provides locking."""
402 
403  return self._getInstanceVarCriticalSection("varAcc")
404 
405  def getMeanGyro(self):
406  """Accessor that provides locking."""
407 
408  return self._getInstanceVarCriticalSection("meanGyro")
409 
410  def getStdevGyro(self):
411  """Accessor that provides locking."""
412 
413  return self._getInstanceVarCriticalSection("stdevGyro")
414 
415  def getVarianceGyro(self):
416  """Accessor that provides locking."""
417 
418  return self._getInstanceVarCriticalSection("varGyro")
419 
420  def _getInstanceVarCriticalSection(self, varName):
421  """Return the value of the given instance variable, providing locking service."""
422 
423  try:
424  self.wiiStateLock.acquire()
425 
426  if varName == "wiimoteState":
427  res = self.wiiMoteState
428  elif varName == "meanAcc":
429  res = self.meanAcc
430  elif varName == "stdevAcc":
431  res = self.stdevAcc
432  elif varName == "varAcc":
433  res = self.varAcc
434  elif varName == "meanGyro":
435  res = self.meanGyro
436  elif varName == "stdevGyro":
437  res = self.stdevGyro
438  elif varName == "varGyro":
439  res = self.varGyroMetric
440  else:
441  raise ValueError("Instance variable name " + str(varName) + "is not under lock control.")
442 
443  finally:
444  self.wiiStateLock.release()
445  return res
446 
447  def setRumble(self, switchPos):
448  """Start of stop rumble (i.e. vibration). 1: start; 0: stop"""
449  self._wm.rumble = switchPos
450 
451  def getRumble(self):
452  # Protect against reading exception from reading
453  # from an already closed device during shutdown:
454  try:
455  return self._wm.state['rumble']
456  except ValueError:
457  pass
458 
459  def setLEDs(self, statusList):
460  """Set the four Wii LEDs according to statusList
461 
462  statusList must be a 4-tuple. Each entry
463  is either True/1, False/0, or None. True (or 1)
464  will turn the respective LED on; False (or 0)
465  turns it off, and None leaves the state unchanged.
466 
467  """
468 
469  currLEDs = self.getLEDs(asInt=True)
470  # Cycle through each LED:
471  for LED in range(len(statusList)):
472  # Should this LED be on?
473  if statusList[LED]:
474  currLEDs = currLEDs | self._LEDMasksOn[LED]
475  # Is this LED to be OFF? (if not, leave it alone)
476  elif statusList[LED] is not None:
477  currLEDs = currLEDs & self._LEDMasksOff[LED]
478  self._wm.led = currLEDs
479 
480  def getLEDs(self, asInt=False):
481  """Get the status of the four Wii LEDs.
482 
483  Return value depends on the asInt parameter:
484  if asInt=False, the method returns a 4-tuple.
485  Each entry is either True or False. True indicates
486  that the respective LED is on; False means off.
487  If asInt=True, return value is a bit vector
488  indicating which LEDs are on.
489 
490  """
491 
492  LEDs = self._wm.state['led']
493  if asInt:
494  return LEDs
495  res = []
496  if LEDs & LED1_ON:
497  res.append(True)
498  else:
499  res.append(False)
500 
501  if LEDs & LED2_ON:
502  res.append(True)
503  else:
504  res.append(False)
505 
506  if LEDs & LED3_ON:
507  res.append(True)
508  else:
509  res.append(False)
510 
511  if LEDs & LED4_ON:
512  res.append(True)
513  else:
514  res.append(False)
515 
516  return res
517 
518  def getBattery(self):
519  """Obtain battery state from Wiimote.
520 
521  Maximum charge is BATTERY_MAX.
522  """
523 
524  return self._wm.state['battery']
525 
527  """Returns currently operative accelerometer calibration.
528 
529  Return value: tuple with calibration for zero reading, and
530  calibration or a '1' reading.
531  """
532  return wiistate.WIIState.getAccelerometerCalibration()
533 
535  """Obtain calibration data from accelerometer.
536 
537  Retrieve factory-installed calibration data for
538  the Wiimote's accelerometer. Returns a two-tuple
539  with the calibration numbers for zero and one:
540 
541  """
542 
543  # Parameter is the Wiimote extension from which
544  # the calibration is to be retrieved.
545 
546  factoryCalNums = self._wm.get_acc_cal(cwiid.EXT_NONE)
547 
548  return (factoryCalNums[0], factoryCalNums[1])
549 
551  """Obtain calibration data from nunchuk accelerometer.
552 
553  Retrieve factory-installed calibration data for
554  the Nunchuk's accelerometer. Returns a two-tuple
555  with the calibration numbers for zero and one:
556 
557  """
558  factoryCalNums = self._wm.get_acc_cal(cwiid.EXT_NUNCHUK)
559  return (factoryCalNums[0], factoryCalNums[1])
560 
561  def setAccelerometerCalibration(self, zeroReadingList, oneReadingList):
562  wiistate.WIIState.setAccelerometerCalibration(np.array(zeroReadingList), np.array(oneReadingList))
563 
564  def setAccelerometerCalibration(self, zeroReadingNPArray, oneReadingNPArray):
565  wiistate.WIIState.setAccelerometerCalibration(zeroReadingNPArray, oneReadingNPArray)
566 
568  """Return current Gyro zeroing offsets as list x/y/z."""
569  return wiistate.WIIState.getGyroCalibration()
570 
571  def setGyroCalibration(self, gyroTriplet):
572  wiistate.WIIState.setGyroCalibration(gyroTriplet)
573 
574  def setNunchukAccelerometerCalibration(self, zeroReadingList, oneReadingList):
575  wiistate.WIIState.setNunchukAccelerometerCalibration(np.array(zeroReadingList), np.array(oneReadingList))
576 
577  def motionPlusPresent(self):
578  """Return True/False to indicate whether a Wiimotion Plus is detected.
579 
580  Note: The return value is accurate only after at least one
581  Wiimote state has been read. This means that either
582  _steadyStateCallback or _calibrationCallback must have
583  run at least once.
584  """
585  if (self.wiiMoteState is not None):
586  return self.wiiMoteState.motionPlusPresent
587  else:
588  return False
589 
590  def nunchukPresent(self):
591  """Return True/False to indicate whether a Nunchuk is detected.
592 
593  Note: The return value is accurate only after at least one
594  Wiimote state has been read. This means that either
595  _steadyStateCallback or _calibrationCallback must have
596  run at least once.
597  """
598  if (self.wiiMoteState is not None):
599  return self.wiiMoteState.nunchukPresent
600  else:
601  return False
602 
604  """Compute mean and stdev for accelerometer data list self._accList in both Gs and metric m/sec^2"""
605 
606  accArrays = []
607  self.maxAccReading = np.array([0, 0, 0], dtype=None, copy=1, order=None, subok=0, ndmin=0)
608  for accWiiReading in self._accList:
609  if accWiiReading is not None:
610  oneAccReading = accWiiReading.tuple()
611  accArrays.append(oneAccReading)
612  self.maxAccReading = np.maximum(self.maxAccReading, np.abs(oneAccReading))
613 
614  # Turn list of numpy triplets into three columns containing
615  # all x, all y, and all z values, respectively:
616  # [array(10,20,30), array(100,200,300)] ==> [[10 20 30],
617  # [100 200 300]]
618  # and take the means of each column. We will end up
619  # with: [55.0 110.0 165.0]
620 
621  self.meanAcc = np.vstack(accArrays).mean(axis=0)
622  self.meanAccMetric = self.meanAcc * EARTH_GRAVITY
623  self.stdevAcc = np.vstack(accArrays).std(axis=0)
624  self.stdevAccMetric = self.stdevAcc * EARTH_GRAVITY
625  self.varAcc = np.square(self.stdevAccMetric)
626 
628  """Compute mean and stdev for gyro data list self._gyroList in both Gs and metric m/sec^2"""
629  gyroArrays = []
630  self.maxGyroReading = np.array([0, 0, 0], dtype=np.float64)
631  for gyroReading in self._gyroList:
632  if (gyroReading is not None):
633  oneGyroReading = gyroReading.tuple()
634  gyroArrays.append(oneGyroReading)
635  self.maxGyroReading = np.maximum(self.maxGyroReading, np.abs(oneGyroReading))
636 
637  if len(gyroArrays) != 0:
638  self.meanGyro = np.vstack(gyroArrays).mean(axis=0)
639  # Convert to radians/sec:
640  self.meanGyroMetric = self.meanGyro * GYRO_SCALE_FACTOR
641  self.stdevGyro = np.vstack(gyroArrays).std(axis=0)
642  # Convert stdev to radians/sec:
643  self.stdevGyroMetric = self.stdevGyro * GYRO_SCALE_FACTOR
644  self.varGyroMetric = np.square(self.stdevGyroMetric)
645 
646  def printState(self):
647  log(self.wiiMoteState)
648 
649  def shutdown(self):
650  self._wm.close()
651 
652 
653 class _WiiCallbackStack(object):
654  """
655  Class organizes installation and removal/restoration
656  of callback functions for the Wii driver to use.
657  Only one instance of this class is allowed. Additional
658  instantiations generate a CallbackStackMultInstError.
659 
660  A stack discipline is imposed. Operations:
661 
662  - push(<callBackFunc>) # New function becomes the active
663  # callback immediately
664  - pop() -> <oldCallBackFunc> # If another function is still on
665  # the stack, it immediately becomes
666  # the active callback. If callback
667  # is paused, resume() is forced.
668  - pause() # Callbacks are temporarily turned off
669  - paused() -> True/False
670  - resume(sloppy=True) # If sloppy=False, resuming when
671  # callbacks are not paused throws an
672  # exception. If sloppy=True, the call is
673  # a no-op
674 
675  """
676  _functionStack = []
677  _singletonInstance = None # No instance exists yet.
678  _paused = False
679 
680  _wm = None # The Wii remote driver instance
681 
682  def __init__(self, wiiDriver, sloppy=True):
683 
684  if self._singletonInstance:
685  if not sloppy:
686  raise CallbackStackMultInstError("Can only instantiate one Wii callback stack.")
687 
688  self._singletonInstance = self
689  self._wm = wiiDriver
690 
691  def push(self, func):
692  """Given function becomes the new WIImote callback function, shadowing
693  the function that is currently on the stack
694  """
695 
696  self._functionStack.append(func)
697  self.setcallback(func)
698 
699  def pop(self):
700  """Wiimote callback function is popped off the stack. New top of stack
701  becomes the new callback function. Old function is returned.
702  """
703 
704  if not self._functionStack:
705  raise CallbackStackEmptyError("Attempt to pop empty callback stack")
706  _paused = False
707  func = self._functionStack.pop()
708  self.setcallback(self._functionStack[-1])
709  return func
710 
711  def pause(self):
712  """WIIMote callbacks are temporarily stopped."""
713 
714  self._wm.disable(cwiid.FLAG_MESG_IFC)
715  self._paused = True
716 
717  def resume(self, sloppy=True):
718  """Resume the (presumably) previously paused WIIMote callback functions.
719  If sloppy is True, this method won't complain if pause was not
720  called earlier. If sloppy is False, an exception is raised in
721  that case.
722  """
723 
724  if not self._paused:
725  if sloppy:
726  return
727  else:
728  raise ResumeNonPausedError("Can't resume without first pausing.")
729 
730  if not self._functionStack:
731  raise CallbackStackEmptyError("Attempt to pop empty callback stack")
732 
733  self._wiiCallbackStack(_functionStack.index[-1])
734 
735  def setcallback(self, f):
736  """Tell WIIMote which function to call when reporting status."""
737 
738  self._wm.mesg_callback = f
739  self._wm.enable(cwiid.FLAG_MESG_IFC)
740 
741 
743 
744  def __init__(self):
745  # runNum, meanAcc, maxAcc, stdevAcc, meanGyro, maxGyro, stdevGyro,
746  # accVal, devAccVal, stdevFractionAccVal, isOutlierAcc,
747  # gyroVal, devGyroVal, stdevFractionGyroVal, isOutlierGyro):
748 
749  pass
750 
751  def setAccData(self, accArray):
752  self.accVal = accArray
753 
754  def setStdevAcc(self, stdevArray):
755  self.stdevAcc = stdevArray
756 
757  def setMeanAcc(self, meanArray):
758  self.meanAcc = meanArray
759 
760  def setMaxAcc(self, maxArray):
761  self.maxAcc = maxArray
762 
763  def setGyroData(self, gyroArray):
764  self.gyroVal = gyroArray
765 
766  def setStdevGyro(self, stdevArray):
767  self.stdevGyro = stdevArray
768 
769  def setMeanGyro(self, meanArray):
770  self.meanGyro = meanArray
771 
772  def setMaxGyro(self, maxArray):
773  self.maxGyro = maxArray
774 
775  def setGyroData(self, gyroVal):
776  self.gyroVal = gyroVal
wiimote.wiimoteExceptions.CallbackStackMultInstError
Definition: wiimoteExceptions.py:36
wiimote.WIIMote.WIIMote.wiiStateLock
wiiStateLock
Definition: WIIMote.py:122
wiimote.WIIMote.WIIMote.getStdevAccelerator
def getStdevAccelerator(self)
Definition: WIIMote.py:395
wiimote.WIIMote.WIIMote._LEDMasksOff
list _LEDMasksOff
Definition: WIIMote.py:89
wiimote.WIIMote.WIIMote.setRumble
def setRumble(self, switchPos)
Definition: WIIMote.py:447
wiimote.WIIMote.WIIMote.shutdown
def shutdown(self)
Definition: WIIMote.py:649
wiimote.WIIMote.CalibrationMeasurements.setStdevAcc
def setStdevAcc(self, stdevArray)
Definition: WIIMote.py:754
wiimote.WIIMote.WIIMote.setNunchukAccelerometerCalibration
def setNunchukAccelerometerCalibration(self, zeroReadingList, oneReadingList)
Definition: WIIMote.py:574
wiimote.WIIMote.WIIMote.__init__
def __init__(self, theSampleRate=0, wiiStateLock=None, gatherCalibrationStats=False)
Definition: WIIMote.py:94
wiimote.WIIMote._WiiCallbackStack.setcallback
def setcallback(self, f)
Definition: WIIMote.py:735
wiimote.WIIMote.WIIMote.getVarianceAccelerator
def getVarianceAccelerator(self)
Definition: WIIMote.py:400
wiimote.WIIMote.WIIMote.getRumble
def getRumble(self)
Definition: WIIMote.py:451
wiimote.WIIMote._WiiCallbackStack.pause
def pause(self)
Definition: WIIMote.py:711
wiimote.WIIMote.WIIMote._wiiCallbackStack
_wiiCallbackStack
Definition: WIIMote.py:74
wiimote.WIIMote.WIIMote.varAcc
varAcc
Definition: WIIMote.py:136
wiimote.WIIMote.WIIMote._startTime
_startTime
Definition: WIIMote.py:76
wiimote.WIIMote.WIIMote._readingsCnt
_readingsCnt
Definition: WIIMote.py:79
wiimote.WIIMote.WIIMote.latestCalibrationSuccessful
latestCalibrationSuccessful
Definition: WIIMote.py:147
wiimote.wiiutils.getTimeStamp
def getTimeStamp()
Definition: wiiutils.py:44
wiimote.WIIMote.WIIMote.printState
def printState(self)
Definition: WIIMote.py:646
wiimote.WIIMote.WIIMote.getAccFactoryCalibrationSettings
def getAccFactoryCalibrationSettings(self)
Definition: WIIMote.py:534
wiimote.WIIMote.CalibrationMeasurements.setMeanGyro
def setMeanGyro(self, meanArray)
Definition: WIIMote.py:769
wiimote.WIIMote.WIIMote._warmupCnt
_warmupCnt
Definition: WIIMote.py:269
wiimote.WIIMote.WIIMote._LEDMasksOn
list _LEDMasksOn
Definition: WIIMote.py:88
wiimote.WIIMote.WIIMote.getAccelerometerCalibration
def getAccelerometerCalibration(self)
Definition: WIIMote.py:526
wiimote.WIIMote._WiiCallbackStack.pop
def pop(self)
Definition: WIIMote.py:699
wiimote.WIIMote.CalibrationMeasurements.__init__
def __init__(self)
Definition: WIIMote.py:744
wiimote.WIIMote.WIIMote.getGyroCalibration
def getGyroCalibration(self)
Definition: WIIMote.py:567
wiimote.WIIMote.CalibrationMeasurements.meanAcc
meanAcc
Definition: WIIMote.py:758
wiimote.wiiutils.promptUsr
def promptUsr(str)
Definition: wiiutils.py:38
wiimote.WIIMote.WIIMote.getMeanGyro
def getMeanGyro(self)
Definition: WIIMote.py:405
wiimote.WIIMote.CalibrationMeasurements.setAccData
def setAccData(self, accArray)
Definition: WIIMote.py:751
wiimote.WIIMote.CalibrationMeasurements.setMaxAcc
def setMaxAcc(self, maxArray)
Definition: WIIMote.py:760
wiimote.WIIMote.CalibrationMeasurements
Definition: WIIMote.py:742
wiimote.WIIMote.CalibrationMeasurements.maxAcc
maxAcc
Definition: WIIMote.py:761
wiimote.wiimoteExceptions.WiimoteEnableError
Definition: wiimoteExceptions.py:32
wiimote.WIIMote.WIIMote.getMeanAccelerator
def getMeanAccelerator(self)
Definition: WIIMote.py:390
wiimote.WIIMote.WIIMote.varGyroMetric
varGyroMetric
Definition: WIIMote.py:145
wiimote.WIIMote.WIIMote._accList
_accList
Definition: WIIMote.py:77
wiimote.WIIMote._WiiCallbackStack._paused
bool _paused
Definition: WIIMote.py:678
wiimote.WIIMote.WIIMote
Definition: WIIMote.py:53
wiimote.WIIMote._WiiCallbackStack._wm
_wm
Definition: WIIMote.py:680
wiimote.WIIMote.WIIMote.getStdevGyro
def getStdevGyro(self)
Definition: WIIMote.py:410
wiimote.WIIMote.WIIMote.getNunchukFactoryCalibrationSettings
def getNunchukFactoryCalibrationSettings(self)
Definition: WIIMote.py:550
wiimote.WIIMote.CalibrationMeasurements.maxGyro
maxGyro
Definition: WIIMote.py:773
wiimote.WIIMote._WiiCallbackStack._functionStack
list _functionStack
Definition: WIIMote.py:676
wiimote.WIIMote.WIIMote.meanAcc
meanAcc
Definition: WIIMote.py:130
wiimote.WIIMote.WIIMote.stdevGyroMetric
stdevGyroMetric
Definition: WIIMote.py:143
wiimote.WIIMote.WIIMote.meanAccMetric
meanAccMetric
Definition: WIIMote.py:131
wiimote.wiiutils.log
def log(str, file=None)
Definition: wiiutils.py:33
wiimote.WIIMote.WIIMote._calibrationCallback
def _calibrationCallback(self, state, theTime)
Definition: WIIMote.py:214
wiimote.WIIMote.WIIMote._getInstanceVarCriticalSection
def _getInstanceVarCriticalSection(self, varName)
Definition: WIIMote.py:420
wiimote.WIIMote._WiiCallbackStack.resume
def resume(self, sloppy=True)
Definition: WIIMote.py:717
wiimote.wiimoteExceptions.WiimoteNotFoundError
Definition: wiimoteExceptions.py:28
wiimote.WIIMote.CalibrationMeasurements.stdevAcc
stdevAcc
Definition: WIIMote.py:755
wiimote.WIIMote.WIIMote.calibrationSamples
calibrationSamples
Definition: WIIMote.py:109
wiimote.WIIMote._WiiCallbackStack._singletonInstance
_singletonInstance
Definition: WIIMote.py:677
wiimote.WIIMote.WIIMote.maxAccReading
maxAccReading
Definition: WIIMote.py:607
wiimote.WIIMote.WIIMote.stdevAcc
stdevAcc
Definition: WIIMote.py:133
wiimote.WIIMote.WIIMote.getWiimoteState
def getWiimoteState(self)
Definition: WIIMote.py:385
wiimote.WIIMote.WIIMote.computeGyroStatistics
def computeGyroStatistics(self)
Definition: WIIMote.py:627
wiimote.wiimoteExceptions.CallbackStackEmptyError
Definition: wiimoteExceptions.py:44
wiimote.WIIMote._WiiCallbackStack.__init__
def __init__(self, wiiDriver, sloppy=True)
Definition: WIIMote.py:682
wiimote.WIIMote.WIIMote.getBattery
def getBattery(self)
Definition: WIIMote.py:518
wiimote.WIIMote.CalibrationMeasurements.meanGyro
meanGyro
Definition: WIIMote.py:770
wiimote.WIIMote._WiiCallbackStack.push
def push(self, func)
Definition: WIIMote.py:691
wiimote.WIIMote.WIIMote.computeAccStatistics
def computeAccStatistics(self)
Definition: WIIMote.py:603
wiimote.WIIMote.WIIMote.wiiMoteState
wiiMoteState
Definition: WIIMote.py:123
wiimote.WIIMote.CalibrationMeasurements.setGyroData
def setGyroData(self, gyroArray)
Definition: WIIMote.py:763
wiimote.WIIMote.WIIMote._nunchukJoyOrig
_nunchukJoyOrig
Definition: WIIMote.py:86
wiimote.WIIMote.WIIMote.sampleRate
sampleRate
Definition: WIIMote.py:124
wiimote.WIIMote.WIIMote.stdevGyro
stdevGyro
Definition: WIIMote.py:142
wiimote.WIIMote.CalibrationMeasurements.accVal
accVal
Definition: WIIMote.py:752
wiimote.WIIMote.WIIMote.meanGyroMetric
meanGyroMetric
Definition: WIIMote.py:140
wiimote.wiistate.WIIState
Definition: wiistate.py:31
wiimote.WIIMote.WIIMote.motionPlusPresent
def motionPlusPresent(self)
Definition: WIIMote.py:577
wiimote.WIIMote.WIIMote.getVarianceGyro
def getVarianceGyro(self)
Definition: WIIMote.py:415
wiimote.WIIMote.WIIMote._wm
_wm
Definition: WIIMote.py:73
wiimote.WIIMote.WIIMote.stdevAccMetric
stdevAccMetric
Definition: WIIMote.py:134
wiimote.WIIMote.WIIMote.nunchukPresent
def nunchukPresent(self)
Definition: WIIMote.py:590
wiimote.WIIMote.WIIMote._steadyStateCallback
def _steadyStateCallback(self, state, theTime)
Definition: WIIMote.py:194
wiimote.WIIMote.WIIMote.zeroDevice
def zeroDevice(self)
Definition: WIIMote.py:245
wiimote.WIIMote.CalibrationMeasurements.setMeanAcc
def setMeanAcc(self, meanArray)
Definition: WIIMote.py:757
wiimote.WIIMote.WIIMote.maxGyroReading
maxGyroReading
Definition: WIIMote.py:630
wiimote.WIIMote.WIIMote.setGyroCalibration
def setGyroCalibration(self, gyroTriplet)
Definition: WIIMote.py:571
wiimote.WIIMote.WIIMote.gatherCalibrationStats
gatherCalibrationStats
Definition: WIIMote.py:107
wiimote.WIIMote.WIIMote.setLEDs
def setLEDs(self, statusList)
Definition: WIIMote.py:459
std
wiimote.WIIMote.WIIMote.lastZeroingTime
lastZeroingTime
Definition: WIIMote.py:105
wiimote.WIIMote.CalibrationMeasurements.setMaxGyro
def setMaxGyro(self, maxArray)
Definition: WIIMote.py:772
wiimote.WIIMote.CalibrationMeasurements.gyroVal
gyroVal
Definition: WIIMote.py:764
wiimote.WIIMote.WIIMote._gyroList
_gyroList
Definition: WIIMote.py:78
wiimote.wiimoteExceptions.ResumeNonPausedError
Definition: wiimoteExceptions.py:40
wiimote.WIIMote.WIIMote.setAccelerometerCalibration
def setAccelerometerCalibration(self, zeroReadingList, oneReadingList)
Definition: WIIMote.py:561
wiimote.WIIMote.WIIMote.meanGyro
meanGyro
Definition: WIIMote.py:139
wiimote.WIIMote._WiiCallbackStack
Definition: WIIMote.py:653
wiimote.WIIMote.WIIMote.getLEDs
def getLEDs(self, asInt=False)
Definition: WIIMote.py:480
wiimote.WIIMote.CalibrationMeasurements.setStdevGyro
def setStdevGyro(self, stdevArray)
Definition: WIIMote.py:766
wiimote.WIIMote.CalibrationMeasurements.stdevGyro
stdevGyro
Definition: WIIMote.py:767


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