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


wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Mon Jun 10 2019 13:42:43