35 """The wiimote_node broadcasts four topics, and listens to messages that control 36 the Wiimote stick's rumble (vibration) and LEDs. Transmitted topics (@100Hz): 38 o wiijoy Messages contain the accelerometer and gyro axis data, and all button states. 39 o imu/data Messages contain the accelerometer and gyro axis data, and covariance matrices 40 o wiimote/state the wiijoy and /imu messages, the button states, the LED states, 41 rumble (i.e. vibrator) state, IR light sensor readings, time since last zeroed, 42 and battery state. See State.msg 43 o imu/is_calibrated Latched message 44 o nunchuk Joy messages using the nunchuk as a joystick 45 o classic Joy messages using the nunchuck as a joystic 47 The node listens to the following messages: 50 Topic that listens to sensor_msgs/JoyFeedbackArray messages. This controls the LEDs and the Rumble. There are 4 LEDs with ids of 0 through 3. The "Player 1" LED is id 0; the "Player 4" LED is id3. The Wiimote only has one rumble, so it is id 0. 52 Request to calibrate the device. 54 No command line parameters. 79 from geometry_msgs.msg
import Vector3
80 from sensor_msgs.msg
import Imu
81 from std_srvs.srv
import Empty
82 from std_srvs.srv
import EmptyResponse
83 from std_msgs.msg
import Bool
84 from sensor_msgs.msg
import Joy
85 from sensor_msgs.msg
import JoyFeedback
86 from sensor_msgs.msg
import JoyFeedbackArray
87 from wiimote.msg
import IrSourceInfo
88 from wiimote.msg
import State
96 GATHER_CALIBRATION_STATS =
True 102 """Initialize the wiimote_node, establishing its name for communication with the Master""" 107 rospy.init_node(
'wiimote', anonymous=
True, log_level=rospy.ERROR)
109 wiimoteDevice.zeroDevice()
112 IMUSender(wiimoteDevice, freq=100).start()
113 JoySender(wiimoteDevice, freq=100).start()
114 WiiSender(wiimoteDevice, freq=100).start()
115 NunSender(wiimoteDevice, freq=100).start()
122 rospy.loginfo(
"Error in startup")
123 rospy.loginfo(sys.exc_info()[0])
126 wiimoteDevice.setRumble(
False)
127 wiimoteDevice.setLEDs([
False,
False,
False,
False])
128 wiimoteDevice.shutdown()
146 threading.Thread.__init__(self)
151 varianceAccelerator = self.wiiMote.getVarianceAccelerator();
153 0., varianceAccelerator[Y], 0.,
154 0., 0., varianceAccelerator[Z]]
156 varianceGyro = self.wiiMote.getVarianceGyro();
158 0., varianceGyro[Y], 0.,
159 0., 0., varianceGyro[Z]]
169 """Retrieve one set of Wiimote measurements from the Wiimote instance. Return scaled accelerator and gyro readings. 171 We canonicalize both accelerator and gyro data through 172 scaling them by constants that turn them into m/sec^2, and 173 radians/sec, respectively. 175 Return: list of canonicalized accelerator and gyro readings. 178 while not rospy.is_shutdown():
180 if self.
wiistate is not None and self.wiistate.acc
is not None:
188 """Scale accelerator, nunchuk accelerator, and gyro readings to be m/sec^2, m/sec^2 and radians/sec, respectively.""" 192 canonicalAccel = self.wiistate.acc.scale(EARTH_GRAVITY)
196 if self.wiistate.nunchukPresent:
197 canonicalNunchukAccel = self.wiistate.nunchukAcc.scale(EARTH_GRAVITY)
199 canonicalNunchukAccel =
None 204 if self.wiistate.motionPlusPresent:
205 canonicalAngleRate = self.wiistate.angleRate.scale(GYRO_SCALE_FACTOR)
207 canonicalAngleRate =
None 209 return [canonicalAccel, canonicalNunchukAccel, canonicalAngleRate]
210 except AttributeError:
213 rospy.loginfo(self.threadName +
" shutting down.")
218 """Broadcasting Wiimote accelerator and gyro readings as IMU messages to Topic sensor_data/Imu""" 221 """Initializes the Wiimote IMU publisher. 224 wiiMote: a bluetooth-connected, calibrated WIIMote instance 225 freq: the message sending frequency in messages/sec. Max is 100, because 226 the Wiimote only samples the sensors at 100Hz. 229 WiimoteDataSender.__init__(self, wiiMote, freq)
231 self.
pub = rospy.Publisher(
'imu/data', Imu, queue_size=1)
234 """Loop that obtains the latest wiimote state, publishes the IMU data, and sleeps. 236 The IMU message, if fully filled in, contains information on orientation, 237 acceleration (in m/s^2), and angular rate (in radians/sec). For each of 238 these quantities, the IMU message format also wants the corresponding 241 Wiimote only gives us acceleration and angular rate. So we ensure that the orientation 242 data entry is marked invalid. We do this by setting the first 243 entry of its associated covariance matrix to -1. The covariance 244 matrices are the 3x3 matrix with the axes' variance in the 245 diagonal. We obtain the variance from the Wiimote instance. 248 rospy.loginfo(
"Wiimote IMU publisher starting (topic /imu/data).")
251 while not rospy.is_shutdown():
252 (canonicalAccel, canonicalNunchukAccel, canonicalAngleRate) = self.
obtainWiimoteData()
254 msg = Imu(header=
None,
256 orientation_covariance=[-1.,0.,0.,0.,0.,0.,0.,0.,0.],
257 angular_velocity=
None,
259 linear_acceleration=
None,
267 if self.wiistate.motionPlusPresent:
268 msg.angular_velocity.x = canonicalAngleRate[PHI]
269 msg.angular_velocity.y = canonicalAngleRate[THETA]
270 msg.angular_velocity.z = canonicalAngleRate[PSI]
274 msg.linear_acceleration.x = canonicalAccel[X]
275 msg.linear_acceleration.y = canonicalAccel[Y]
276 msg.linear_acceleration.z = canonicalAccel[Z]
278 measureTime = self.wiistate.time
279 timeSecs = int(measureTime)
280 timeNSecs = int(abs(timeSecs - measureTime) * 10**9)
281 msg.header.stamp.secs = timeSecs
282 msg.header.stamp.nsecs = timeNSecs
285 self.pub.publish(msg)
286 except rospy.ROSException:
287 rospy.loginfo(
"Topic imu/data closed. Shutting down Imu sender.")
293 except rospy.ROSInterruptException:
294 rospy.loginfo(
"Shutdown request. Shutting down Imu sender.")
300 """Broadcasting Wiimote accelerator and gyro readings as Joy(stick) messages to Topic joy""" 303 """Initializes the Wiimote Joy(stick) publisher. 306 wiiMote: a bluetooth-connected, calibrated WIIMote instance 307 freq: the message sending frequency in messages/sec. Max is 100, because 308 the Wiimote only samples the sensors at 100Hz. 311 WiimoteDataSender.__init__(self, wiiMote, freq)
314 self.
pub = rospy.Publisher(
'joy', Joy, queue_size=1)
317 """Loop that obtains the latest wiimote state, publishes the joystick data, and sleeps. 319 The Joy.msg message types calls for just two fields: float32[] axes, and int32[] buttons. 322 rospy.loginfo(
"Wiimote joystick publisher starting (topic wiijoy).")
325 while not rospy.is_shutdown():
326 (canonicalAccel, canonicalNunchukAccel, canonicalAngleRate) = self.
obtainWiimoteData()
328 msg = Joy(header=
None,
329 axes=[canonicalAccel[X], canonicalAccel[Y], canonicalAccel[Z]],
334 if self.wiistate.motionPlusPresent:
335 msg.axes.extend([canonicalAngleRate[PHI], canonicalAngleRate[THETA], canonicalAngleRate[PSI]])
340 theButtons = [
False,
False,
False,
False,
False,
False,
False,
False,
False,
False,
False]
341 theButtons[State.MSG_BTN_1] = self.wiistate.buttons[BTN_1]
342 theButtons[State.MSG_BTN_2] = self.wiistate.buttons[BTN_2]
343 theButtons[State.MSG_BTN_A] = self.wiistate.buttons[BTN_A]
344 theButtons[State.MSG_BTN_B] = self.wiistate.buttons[BTN_B]
345 theButtons[State.MSG_BTN_PLUS] = self.wiistate.buttons[BTN_PLUS]
346 theButtons[State.MSG_BTN_MINUS] = self.wiistate.buttons[BTN_MINUS]
347 theButtons[State.MSG_BTN_LEFT] = self.wiistate.buttons[BTN_LEFT]
348 theButtons[State.MSG_BTN_RIGHT] = self.wiistate.buttons[BTN_RIGHT]
349 theButtons[State.MSG_BTN_UP] = self.wiistate.buttons[BTN_UP]
350 theButtons[State.MSG_BTN_DOWN] = self.wiistate.buttons[BTN_DOWN]
351 theButtons[State.MSG_BTN_HOME] = self.wiistate.buttons[BTN_HOME]
353 msg.buttons = theButtons
355 measureTime = self.wiistate.time
356 timeSecs = int(measureTime)
357 timeNSecs = int(abs(timeSecs - measureTime) * 10**9)
359 msg.header.stamp.secs = timeSecs
360 msg.header.stamp.nsecs = timeNSecs
363 self.pub.publish(msg)
364 except rospy.ROSException:
365 rospy.loginfo(
"Topic wiijoy closed. Shutting down Joy sender.")
371 except rospy.ROSInterruptException:
372 rospy.loginfo(
"Shutdown request. Shutting down Joy sender.")
377 """Broadcasting nunchuk accelerator and joystick readings as Joy(stick) messages to Topic joy""" 380 """Initializes the nunchuk Joy(stick) publisher. 383 wiiMote: a bluetooth-connected, calibrated WIIMote instance 384 freq: the message sending frequency in messages/sec. Max is 100, because 385 the Wiimote only samples the sensors at 100Hz. 388 WiimoteDataSender.__init__(self, wiiMote, freq)
397 """Loop that obtains the latest nunchuk state, publishes the joystick data, and sleeps. 399 The Joy.msg message types calls for just two fields: float32[] axes, and int32[] buttons. 404 while not rospy.is_shutdown():
407 if not self.wiistate.nunchukPresent:
410 self.
pub = rospy.Publisher(
'/wiimote/nunchuk', Joy, queue_size=1)
411 rospy.loginfo(
"Wiimote Nunchuk joystick publisher starting (topic nunchuk).")
413 (joyx, joyy) = self.wiistate.nunchukStick
415 msg = Joy(header=
None,
417 scaledAcc[X], scaledAcc[Y], scaledAcc[Z]],
420 theButtons = [
False,
False]
421 theButtons[State.MSG_BTN_Z] = self.wiistate.nunchukButtons[BTN_Z]
422 theButtons[State.MSG_BTN_C] = self.wiistate.nunchukButtons[BTN_C]
424 msg.buttons = theButtons
426 measureTime = self.wiistate.time
427 timeSecs = int(measureTime)
428 timeNSecs = int(abs(timeSecs - measureTime) * 10**9)
429 msg.header.stamp.secs = timeSecs
430 msg.header.stamp.nsecs = timeNSecs
433 self.pub.publish(msg)
434 except rospy.ROSException:
435 rospy.loginfo(
"Topic /wiimote/nunchuk closed. Shutting down Nun sender.")
441 except rospy.ROSInterruptException:
442 rospy.loginfo(
"Shutdown request. Shutting down Nun sender.")
447 """Broadcasting Classic Controller joystick readings as Joy(stick) messages to Topic joy""" 450 """Initializes the Classic Controller Joy(stick) publisher. 453 wiiMote: a bluetooth-connected, calibrated WIIMote instance 454 freq: the message sending frequency in messages/sec. Max is 100, because 455 the Wiimote only samples the sensors at 100Hz. 458 WiimoteDataSender.__init__(self, wiiMote, freq)
465 """Loop that obtains the latest classic controller state, publishes the joystick data, and sleeps. 467 The Joy.msg message types calls for just two fields: float32[] axes, and int32[] buttons. 470 self.threadName =
"Classic Controller Joy topic Publisher" 472 while not rospy.is_shutdown():
473 rospy.sleep(self.sleepDuration)
474 self.obtainWiimoteData()
476 if not self.wiistate.classicPresent:
479 self.pub = rospy.Publisher(
'/wiimote/classic', Joy)
480 rospy.loginfo(
"Wiimote Classic Controller joystick publisher starting (topic /wiimote/classic).")
482 (l_joyx, l_joyy) = self.wiistate.classicStickLeft
483 (r_joyx, r_joyy) = self.wiistate.classicStickRight
485 l_joyx = -(l_joyx-33)/27.
486 l_joyy = (l_joyy-33)/27.
487 r_joyx = -(r_joyx-15)/13.
488 r_joyy = (r_joyy-15)/13.
490 if abs(l_joyx) < .05:
492 if abs(l_joyy) < .05:
494 if abs(r_joyx) < .05:
496 if abs(r_joyy) < .05:
499 msg = Joy(header=
None,
500 axes=[l_joyx, l_joyy,r_joyx, r_joyy],
503 theButtons = [
False,
False,
False,
False,
False,
False,
False,
False,
False,
False,
False,
False,
False,
False,
False]
504 theButtons[State.MSG_CLASSIC_BTN_X] = self.wiistate.classicButtons[CLASSIC_BTN_X]
505 theButtons[State.MSG_CLASSIC_BTN_Y] = self.wiistate.classicButtons[CLASSIC_BTN_Y]
506 theButtons[State.MSG_CLASSIC_BTN_A] = self.wiistate.classicButtons[CLASSIC_BTN_A]
507 theButtons[State.MSG_CLASSIC_BTN_B] = self.wiistate.classicButtons[CLASSIC_BTN_B]
508 theButtons[State.MSG_CLASSIC_BTN_PLUS] = self.wiistate.classicButtons[CLASSIC_BTN_PLUS]
509 theButtons[State.MSG_CLASSIC_BTN_MINUS] = self.wiistate.classicButtons[CLASSIC_BTN_MINUS]
510 theButtons[State.MSG_CLASSIC_BTN_LEFT] = self.wiistate.classicButtons[CLASSIC_BTN_LEFT]
511 theButtons[State.MSG_CLASSIC_BTN_RIGHT] = self.wiistate.classicButtons[CLASSIC_BTN_RIGHT]
512 theButtons[State.MSG_CLASSIC_BTN_UP] = self.wiistate.classicButtons[CLASSIC_BTN_UP]
513 theButtons[State.MSG_CLASSIC_BTN_DOWN] = self.wiistate.classicButtons[CLASSIC_BTN_DOWN]
514 theButtons[State.MSG_CLASSIC_BTN_HOME] = self.wiistate.classicButtons[CLASSIC_BTN_HOME]
515 theButtons[State.MSG_CLASSIC_BTN_L] = self.wiistate.classicButtons[CLASSIC_BTN_L]
516 theButtons[State.MSG_CLASSIC_BTN_R] = self.wiistate.classicButtons[CLASSIC_BTN_R]
517 theButtons[State.MSG_CLASSIC_BTN_ZL] = self.wiistate.classicButtons[CLASSIC_BTN_ZL]
518 theButtons[State.MSG_CLASSIC_BTN_ZR] = self.wiistate.classicButtons[CLASSIC_BTN_ZR]
520 msg.buttons = theButtons
522 measureTime = self.wiistate.time
523 timeSecs = int(measureTime)
524 timeNSecs = int(abs(timeSecs - measureTime) * 10**9)
525 msg.header.stamp.secs = timeSecs
526 msg.header.stamp.nsecs = timeNSecs
529 self.pub.publish(msg)
530 except rospy.ROSException:
531 rospy.loginfo(
"Topic /wiimote/classic closed. Shutting down Clas sender.")
537 except rospy.ROSInterruptException:
538 rospy.loginfo(
"Shutdown request. Shutting down Clas sender.")
543 """Broadcasting complete Wiimote messages to Topic wiimote""" 546 """Initializes the full-Wiimote publisher. 549 wiiMote: a bluetooth-connected, calibrated WIIMote instance 550 freq: the message sending frequency in messages/sec. Max is 100, because 551 the Wiimote only samples the sensors at 100Hz. 554 WiimoteDataSender.__init__(self, wiiMote, freq)
556 self.
pub = rospy.Publisher(
'/wiimote/state', State, queue_size=1)
559 """Loop that obtains the latest wiimote state, publishes the data, and sleeps. 561 The wiimote message, if fully filled in, contains information in common with Imu.msg: 562 acceleration (in m/s^2), and angular rate (in radians/sec). For each of 563 these quantities, the IMU message format also wants the corresponding 566 The covariance matrices are the 3x3 matrix with the axes' variance in the 567 diagonal. We obtain the variance from the Wiimote instance. 570 rospy.loginfo(
"Wiimote state publisher starting (topic /wiimote/state).")
573 while not rospy.is_shutdown():
575 (canonicalAccel, canonicalNunchukAccel, canonicalAngleRate) = self.
obtainWiimoteData()
577 zeroingTimeSecs = int(self.wiiMote.lastZeroingTime)
578 zeroingTimeNSecs = int((self.wiiMote.lastZeroingTime - zeroingTimeSecs) * 10**9)
579 msg = State(header=
None,
580 angular_velocity_zeroed=
None,
581 angular_velocity_raw=
None,
583 linear_acceleration_zeroed=
None,
584 linear_acceleration_raw=
None,
586 nunchuk_acceleration_zeroed=
None,
587 nunchuk_acceleration_raw=
None,
588 nunchuk_joystick_zeroed=
None,
589 nunchuk_joystick_raw=
None,
590 buttons=[
False,
False,
False,
False,
False,
False,
False,
False,
False,
False],
591 nunchuk_buttons=[
False,
False],
596 percent_battery=
None,
597 zeroing_time=rospy.Time(zeroingTimeSecs, zeroingTimeNSecs),
604 if self.wiistate.motionPlusPresent:
605 msg.angular_velocity_zeroed.x = canonicalAngleRate[PHI]
606 msg.angular_velocity_zeroed.y = canonicalAngleRate[THETA]
607 msg.angular_velocity_zeroed.z = canonicalAngleRate[PSI]
609 msg.angular_velocity_raw.x = self.wiistate.angleRateRaw[PHI]
610 msg.angular_velocity_raw.y = self.wiistate.angleRateRaw[THETA]
611 msg.angular_velocity_raw.z = self.wiistate.angleRateRaw[PSI]
616 msg.linear_acceleration_zeroed.x = canonicalAccel[X]
617 msg.linear_acceleration_zeroed.y = canonicalAccel[Y]
618 msg.linear_acceleration_zeroed.z = canonicalAccel[Z]
620 msg.linear_acceleration_raw.x = self.wiistate.accRaw[X]
621 msg.linear_acceleration_raw.y = self.wiistate.accRaw[Y]
622 msg.linear_acceleration_raw.z = self.wiistate.accRaw[Z]
624 if self.wiistate.nunchukPresent:
625 msg.nunchuk_acceleration_zeroed.x = canonicalNunchukAccel[X]
626 msg.nunchuk_acceleration_zeroed.y = canonicalNunchukAccel[Y]
627 msg.nunchuk_acceleration_zeroed.z = canonicalNunchukAccel[Z]
629 msg.nunchuk_acceleration_raw.x = self.wiistate.nunchukAccRaw[X]
630 msg.nunchuk_acceleration_raw.y = self.wiistate.nunchukAccRaw[Y]
631 msg.nunchuk_acceleration_raw.z = self.wiistate.nunchukAccRaw[Z]
633 msg.nunchuk_joystick_zeroed = self.wiistate.nunchukStick
634 msg.nunchuk_joystick_raw = self.wiistate.nunchukStickRaw
636 moreButtons.append(self.wiistate.nunchukButtons[BTN_Z])
637 moreButtons.append(self.wiistate.nunchukButtons[BTN_C])
638 msg.nunchuk_buttons = moreButtons
641 theButtons.append(self.wiistate.buttons[BTN_1])
642 theButtons.append(self.wiistate.buttons[BTN_2])
643 theButtons.append(self.wiistate.buttons[BTN_PLUS])
644 theButtons.append(self.wiistate.buttons[BTN_MINUS])
645 theButtons.append(self.wiistate.buttons[BTN_A])
646 theButtons.append(self.wiistate.buttons[BTN_B])
647 theButtons.append(self.wiistate.buttons[BTN_UP])
648 theButtons.append(self.wiistate.buttons[BTN_DOWN])
649 theButtons.append(self.wiistate.buttons[BTN_LEFT])
650 theButtons.append(self.wiistate.buttons[BTN_RIGHT])
651 theButtons.append(self.wiistate.buttons[BTN_HOME])
653 ledStates = self.wiiMote.getLEDs()
654 for indx
in range(len(msg.LEDs)):
656 msg.LEDs[indx] =
True 658 msg.LEDs[indx] =
False 660 msg.buttons = theButtons
662 msg.raw_battery = self.wiiMote.getBattery()
663 msg.percent_battery = msg.raw_battery * 100./self.wiiMote.BATTERY_MAX
665 irSources = self.wiistate.IRSources
667 for irSensorIndx
in range(NUM_IR_SENSORS):
668 if irSources[irSensorIndx]
is not None:
671 pos = irSources[irSensorIndx][
'pos']
674 msg.ir_tracking.append(IrSourceInfo(State.INVALID_FLOAT, State.INVALID_FLOAT, State.INVALID))
680 size = irSources[irSensorIndx][
'size']
684 lightInfo = IrSourceInfo(pos[0], pos[1], size)
685 msg.ir_tracking.append(lightInfo)
687 msg.ir_tracking.append(IrSourceInfo(State.INVALID_FLOAT, State.INVALID_FLOAT, State.INVALID))
689 measureTime = self.wiistate.time
690 timeSecs = int(measureTime)
691 timeNSecs = int(abs(timeSecs - measureTime) * 10**9)
692 msg.header.stamp.secs = timeSecs
693 msg.header.stamp.nsecs = timeNSecs
696 self.pub.publish(msg)
697 except rospy.ROSException:
698 rospy.loginfo(
"Topic /wiimote/state closed. Shutting down Wiimote sender.")
707 except rospy.ROSInterruptException:
708 rospy.loginfo(
"Shutdown request. Shutting down Wiimote sender.")
712 """Listen for request to rumble and LED blinking. 717 threading.Thread.__init__(self)
736 self.is_CalibratedResponseMsg.data = self.wiiMote.latestCalibrationSuccessful;
741 def feedbackCallback(msg):
742 """The callback for handle the feedback array messages and sending that to the Wiimote""" 744 if fb.type == JoyFeedback.TYPE_LED:
746 if fb.intensity >= 0.5:
751 rospy.logwarn(
"LED ID out of bounds, ignoring!")
752 elif fb.type == JoyFeedback.TYPE_RUMBLE:
754 if fb.intensity >= 0.5:
759 rospy.logwarn(
"RUMBLE ID out of bounds, ignoring!")
768 def calibrateCallback(req):
769 """The imu/calibrate service handler.""" 771 rospy.loginfo(
"Calibration request")
773 calibrationSuccess = self.wiiMote.zeroDevice()
777 self.is_CalibratedResponseMsg.data = calibrationSuccess
780 return EmptyResponse()
786 rospy.loginfo(
"Wiimote feedback listener starting (topic /joy/set_feedback).")
787 rospy.Subscriber(
"joy/set_feedback", JoyFeedbackArray, feedbackCallback)
788 rospy.loginfo(
"Wiimote calibration service starting (topic /imu/calibrate).")
789 rospy.Service(
"imu/calibrate", Empty, calibrateCallback)
790 rospy.loginfo(
"Wiimote latched is_calibrated publisher starting (topic /imu/is_calibrated).")
794 except rospy.ROSInterruptException:
795 rospy.loginfo(
"Shutdown request. Shutting down Wiimote listeners.")
799 if __name__ ==
'__main__':
802 wiimoteNode.runWiimoteNode()
804 except rospy.ROSInterruptException:
805 rospy.loginfo(
"ROS Shutdown Request.")
806 except KeyboardInterrupt, e:
807 rospy.loginfo(
"Received keyboard interrupt.")
808 except WiimoteNotFoundError, e:
809 rospy.logfatal(str(e))
810 except WiimoteEnableError, e:
811 rospy.logfatal(str(e))
812 except CallbackStackMultInstError, e:
813 rospy.logfatal(str(e))
814 except CallbackStackEmptyError, e:
815 rospy.logfatal(str(e))
816 except ResumeNonPausedError, e:
817 rospy.logfatal(str(e))
818 except CallbackStackEmptyError, e:
819 rospy.logfatal(str(e))
822 excType, excValue, excTraceback = sys.exc_info()[:3]
823 traceback.print_exception(excType, excValue, excTraceback)
825 if (wiimoteNode
is not None):
826 wiimoteNode.shutdown()
827 rospy.loginfo(
"Exiting Wiimote node.")
def __init__(self, wiiMote, freq=100)
def __init__(self, wiiMote, freq=100)
def __init__(self, wiiMote, freq=100)
def __init__(self, wiiMote, freq=100)
def obtainWiimoteData(self)
def __init__(self, wiiMote)
linear_acceleration_covariance
angular_velocity_covariance
def __init__(self, wiiMote, freq=100)
def canonicalizeWiistate(self)
def __init__(self, wiiMote, freq=100)