00001 """autogenerated by genpy from wiimote/State.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import wiimote.msg
00008 import geometry_msgs.msg
00009 import genpy
00010 import std_msgs.msg
00011
00012 class State(genpy.Message):
00013 _md5sum = "a69651e8129655c6ed3c5039e468362c"
00014 _type = "wiimote/State"
00015 _has_header = True
00016 _full_text = """#
00017 # Wiimote State message containing one complete Wiimote state
00018
00019 # Note: For ease of manipulation this message often uses
00020 # int8[] when a bit vector would work. One might
00021 # wish to use uint8[], but then Python takes
00022 # the respective structure as a string and disallows
00023 # item assignment.
00024
00025 int8 INVALID = -1
00026 float32 INVALID_FLOAT = -1.0
00027
00028 int8 MSG_BTN_1 = 0
00029 int8 MSG_BTN_2 = 1
00030 int8 MSG_BTN_A = 2
00031 int8 MSG_BTN_B = 3
00032 int8 MSG_BTN_PLUS = 4
00033 int8 MSG_BTN_MINUS = 5
00034 int8 MSG_BTN_LEFT = 6
00035 int8 MSG_BTN_RIGHT = 7
00036 int8 MSG_BTN_UP = 8
00037 int8 MSG_BTN_DOWN = 9
00038 int8 MSG_BTN_HOME = 10
00039 int8 MSG_BTN_Z = 0
00040 int8 MSG_BTN_C = 1
00041 int8 MSG_CLASSIC_BTN_X = 0
00042 int8 MSG_CLASSIC_BTN_Y = 1
00043 int8 MSG_CLASSIC_BTN_A = 2
00044 int8 MSG_CLASSIC_BTN_B = 3
00045 int8 MSG_CLASSIC_BTN_PLUS = 4
00046 int8 MSG_CLASSIC_BTN_MINUS = 5
00047 int8 MSG_CLASSIC_BTN_LEFT = 6
00048 int8 MSG_CLASSIC_BTN_RIGHT = 7
00049 int8 MSG_CLASSIC_BTN_UP = 8
00050 int8 MSG_CLASSIC_BTN_DOWN = 9
00051 int8 MSG_CLASSIC_BTN_HOME = 10
00052 int8 MSG_CLASSIC_BTN_L = 11
00053 int8 MSG_CLASSIC_BTN_R = 12
00054 int8 MSG_CLASSIC_BTN_ZL = 13
00055 int8 MSG_CLASSIC_BTN_ZR = 14
00056
00057 #-----------------------------
00058 # Header
00059 #----------------------
00060
00061 Header header
00062
00063 #----------------------
00064 # Gyro reading
00065 #-----------------------------
00066 # In radians/sec. If reading is invalid,
00067 # for instance b/c no gyro is attached to the Wii, then
00068 # set first element of covariance to -1 (same as imu_data.msg):
00069 # Covariance matrix (roll, pitch, yaw) in radians^2/sec^2.
00070
00071 geometry_msgs/Vector3 angular_velocity_zeroed
00072 geometry_msgs/Vector3 angular_velocity_raw
00073 float64[9] angular_velocity_covariance
00074
00075 #----------------------
00076 # Accelerometer reading
00077 #-----------------------------
00078 # Acceleration in m/sec^2. Covariance matrix
00079 # (x,y,z) in m^2/sec^4. (all same as imu_data.msg)
00080
00081 geometry_msgs/Vector3 linear_acceleration_zeroed
00082 geometry_msgs/Vector3 linear_acceleration_raw
00083 float64[9] linear_acceleration_covariance
00084
00085 #------------------------------
00086 # Nunchuk Accelerometer reading
00087 #------------------------------
00088 geometry_msgs/Vector3 nunchuk_acceleration_zeroed
00089 geometry_msgs/Vector3 nunchuk_acceleration_raw
00090
00091 #-----------------
00092 # Nunchuk Joystick
00093 #-----------------
00094 float32[2] nunchuk_joystick_zeroed
00095 float32[2] nunchuk_joystick_raw
00096
00097 #----------------------
00098 # Wiimote buttons
00099 #-----------------------------
00100 # Mappings from Wiimote button name
00101 # to array position are defined above.
00102 #
00103 bool[11] buttons
00104 bool[2] nunchuk_buttons
00105
00106 #----------------------
00107 # Wiimote LED states:
00108 #-----------------------------
00109
00110 bool[4] LEDs
00111
00112 #----------------------
00113 # Wiimote Rumble
00114 #-----------------------------
00115 # State (True or False)
00116
00117 bool rumble
00118
00119 #----------------------
00120 # IR Light sensor (Camera)
00121 #-----------------------------
00122 # The Wiimote handles up to four light sources,
00123 # and the wiimote_node.py software is written to
00124 # that limit as well. For future expansion
00125 # we make the following array extensible, rather
00126 # than locking its length down to four:
00127
00128 wiimote/IrSourceInfo[] ir_tracking
00129
00130 #----------------------
00131 # Wiimote battery
00132 #-----------------------------
00133 # A battery reading consists of two numbers:
00134 # the battery percentage, and the raw reading.
00135 # Maximum battery is 208 units (unknown how this
00136 # relates to electrical properties):
00137
00138 float32 raw_battery
00139 float32 percent_battery
00140
00141 #----------------------
00142 # Time of most recent zeroing:
00143 #-----------------------------
00144
00145 time zeroing_time
00146
00147 #----------------------
00148 # Error vector
00149 #-----------------------------
00150 # For error condition definitions see wiimoteConstants.py
00151 # Value of zero means all is well. (Currently NOT used).
00152
00153 uint64 errors
00154
00155 ================================================================================
00156 MSG: std_msgs/Header
00157 # Standard metadata for higher-level stamped data types.
00158 # This is generally used to communicate timestamped data
00159 # in a particular coordinate frame.
00160 #
00161 # sequence ID: consecutively increasing ID
00162 uint32 seq
00163 #Two-integer timestamp that is expressed as:
00164 # * stamp.secs: seconds (stamp_secs) since epoch
00165 # * stamp.nsecs: nanoseconds since stamp_secs
00166 # time-handling sugar is provided by the client library
00167 time stamp
00168 #Frame this data is associated with
00169 # 0: no frame
00170 # 1: global frame
00171 string frame_id
00172
00173 ================================================================================
00174 MSG: geometry_msgs/Vector3
00175 # This represents a vector in free space.
00176
00177 float64 x
00178 float64 y
00179 float64 z
00180 ================================================================================
00181 MSG: wiimote/IrSourceInfo
00182 # Sensor data pertaining to the Wiimote infrared camera.
00183 # This message contains data for one of the four infrared
00184 # light sources that the camera detects.
00185 #
00186 # Each light is specified with a 2D position and
00187 # a 'source magnitude' (ir_size). If the x dimension
00188 # is set to INVALID_FLOAT, then no light was detected for
00189 # the respective light. The Wiimote handles up to
00190 # four light sources, and the wiimote_node.py software
00191 # is written to that limit as well.
00192 #
00193 # I am unsure what the 'ir_size' values represent.
00194 # They are described as 'source magnitude' in some places. I
00195 # *assume* this is signal amplitude, but it's unclear.
00196 # Note that current lowest level cwiid driver does not
00197 # seem to pass the ir_size value to the cwiid Wiimote.c.
00198 # For now this size will therefore be set INVALID
00199
00200 float64 x
00201 float64 y
00202 int64 ir_size
00203
00204 """
00205
00206 INVALID = -1
00207 INVALID_FLOAT = -1.0
00208 MSG_BTN_1 = 0
00209 MSG_BTN_2 = 1
00210 MSG_BTN_A = 2
00211 MSG_BTN_B = 3
00212 MSG_BTN_PLUS = 4
00213 MSG_BTN_MINUS = 5
00214 MSG_BTN_LEFT = 6
00215 MSG_BTN_RIGHT = 7
00216 MSG_BTN_UP = 8
00217 MSG_BTN_DOWN = 9
00218 MSG_BTN_HOME = 10
00219 MSG_BTN_Z = 0
00220 MSG_BTN_C = 1
00221 MSG_CLASSIC_BTN_X = 0
00222 MSG_CLASSIC_BTN_Y = 1
00223 MSG_CLASSIC_BTN_A = 2
00224 MSG_CLASSIC_BTN_B = 3
00225 MSG_CLASSIC_BTN_PLUS = 4
00226 MSG_CLASSIC_BTN_MINUS = 5
00227 MSG_CLASSIC_BTN_LEFT = 6
00228 MSG_CLASSIC_BTN_RIGHT = 7
00229 MSG_CLASSIC_BTN_UP = 8
00230 MSG_CLASSIC_BTN_DOWN = 9
00231 MSG_CLASSIC_BTN_HOME = 10
00232 MSG_CLASSIC_BTN_L = 11
00233 MSG_CLASSIC_BTN_R = 12
00234 MSG_CLASSIC_BTN_ZL = 13
00235 MSG_CLASSIC_BTN_ZR = 14
00236
00237 __slots__ = ['header','angular_velocity_zeroed','angular_velocity_raw','angular_velocity_covariance','linear_acceleration_zeroed','linear_acceleration_raw','linear_acceleration_covariance','nunchuk_acceleration_zeroed','nunchuk_acceleration_raw','nunchuk_joystick_zeroed','nunchuk_joystick_raw','buttons','nunchuk_buttons','LEDs','rumble','ir_tracking','raw_battery','percent_battery','zeroing_time','errors']
00238 _slot_types = ['std_msgs/Header','geometry_msgs/Vector3','geometry_msgs/Vector3','float64[9]','geometry_msgs/Vector3','geometry_msgs/Vector3','float64[9]','geometry_msgs/Vector3','geometry_msgs/Vector3','float32[2]','float32[2]','bool[11]','bool[2]','bool[4]','bool','wiimote/IrSourceInfo[]','float32','float32','time','uint64']
00239
00240 def __init__(self, *args, **kwds):
00241 """
00242 Constructor. Any message fields that are implicitly/explicitly
00243 set to None will be assigned a default value. The recommend
00244 use is keyword arguments as this is more robust to future message
00245 changes. You cannot mix in-order arguments and keyword arguments.
00246
00247 The available fields are:
00248 header,angular_velocity_zeroed,angular_velocity_raw,angular_velocity_covariance,linear_acceleration_zeroed,linear_acceleration_raw,linear_acceleration_covariance,nunchuk_acceleration_zeroed,nunchuk_acceleration_raw,nunchuk_joystick_zeroed,nunchuk_joystick_raw,buttons,nunchuk_buttons,LEDs,rumble,ir_tracking,raw_battery,percent_battery,zeroing_time,errors
00249
00250 :param args: complete set of field values, in .msg order
00251 :param kwds: use keyword arguments corresponding to message field names
00252 to set specific fields.
00253 """
00254 if args or kwds:
00255 super(State, self).__init__(*args, **kwds)
00256
00257 if self.header is None:
00258 self.header = std_msgs.msg.Header()
00259 if self.angular_velocity_zeroed is None:
00260 self.angular_velocity_zeroed = geometry_msgs.msg.Vector3()
00261 if self.angular_velocity_raw is None:
00262 self.angular_velocity_raw = geometry_msgs.msg.Vector3()
00263 if self.angular_velocity_covariance is None:
00264 self.angular_velocity_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00265 if self.linear_acceleration_zeroed is None:
00266 self.linear_acceleration_zeroed = geometry_msgs.msg.Vector3()
00267 if self.linear_acceleration_raw is None:
00268 self.linear_acceleration_raw = geometry_msgs.msg.Vector3()
00269 if self.linear_acceleration_covariance is None:
00270 self.linear_acceleration_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00271 if self.nunchuk_acceleration_zeroed is None:
00272 self.nunchuk_acceleration_zeroed = geometry_msgs.msg.Vector3()
00273 if self.nunchuk_acceleration_raw is None:
00274 self.nunchuk_acceleration_raw = geometry_msgs.msg.Vector3()
00275 if self.nunchuk_joystick_zeroed is None:
00276 self.nunchuk_joystick_zeroed = [0.,0.]
00277 if self.nunchuk_joystick_raw is None:
00278 self.nunchuk_joystick_raw = [0.,0.]
00279 if self.buttons is None:
00280 self.buttons = [False,False,False,False,False,False,False,False,False,False,False]
00281 if self.nunchuk_buttons is None:
00282 self.nunchuk_buttons = [False,False]
00283 if self.LEDs is None:
00284 self.LEDs = [False,False,False,False]
00285 if self.rumble is None:
00286 self.rumble = False
00287 if self.ir_tracking is None:
00288 self.ir_tracking = []
00289 if self.raw_battery is None:
00290 self.raw_battery = 0.
00291 if self.percent_battery is None:
00292 self.percent_battery = 0.
00293 if self.zeroing_time is None:
00294 self.zeroing_time = genpy.Time()
00295 if self.errors is None:
00296 self.errors = 0
00297 else:
00298 self.header = std_msgs.msg.Header()
00299 self.angular_velocity_zeroed = geometry_msgs.msg.Vector3()
00300 self.angular_velocity_raw = geometry_msgs.msg.Vector3()
00301 self.angular_velocity_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00302 self.linear_acceleration_zeroed = geometry_msgs.msg.Vector3()
00303 self.linear_acceleration_raw = geometry_msgs.msg.Vector3()
00304 self.linear_acceleration_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00305 self.nunchuk_acceleration_zeroed = geometry_msgs.msg.Vector3()
00306 self.nunchuk_acceleration_raw = geometry_msgs.msg.Vector3()
00307 self.nunchuk_joystick_zeroed = [0.,0.]
00308 self.nunchuk_joystick_raw = [0.,0.]
00309 self.buttons = [False,False,False,False,False,False,False,False,False,False,False]
00310 self.nunchuk_buttons = [False,False]
00311 self.LEDs = [False,False,False,False]
00312 self.rumble = False
00313 self.ir_tracking = []
00314 self.raw_battery = 0.
00315 self.percent_battery = 0.
00316 self.zeroing_time = genpy.Time()
00317 self.errors = 0
00318
00319 def _get_types(self):
00320 """
00321 internal API method
00322 """
00323 return self._slot_types
00324
00325 def serialize(self, buff):
00326 """
00327 serialize message into buffer
00328 :param buff: buffer, ``StringIO``
00329 """
00330 try:
00331 _x = self
00332 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00333 _x = self.header.frame_id
00334 length = len(_x)
00335 if python3 or type(_x) == unicode:
00336 _x = _x.encode('utf-8')
00337 length = len(_x)
00338 buff.write(struct.pack('<I%ss'%length, length, _x))
00339 _x = self
00340 buff.write(_struct_6d.pack(_x.angular_velocity_zeroed.x, _x.angular_velocity_zeroed.y, _x.angular_velocity_zeroed.z, _x.angular_velocity_raw.x, _x.angular_velocity_raw.y, _x.angular_velocity_raw.z))
00341 buff.write(_struct_9d.pack(*self.angular_velocity_covariance))
00342 _x = self
00343 buff.write(_struct_6d.pack(_x.linear_acceleration_zeroed.x, _x.linear_acceleration_zeroed.y, _x.linear_acceleration_zeroed.z, _x.linear_acceleration_raw.x, _x.linear_acceleration_raw.y, _x.linear_acceleration_raw.z))
00344 buff.write(_struct_9d.pack(*self.linear_acceleration_covariance))
00345 _x = self
00346 buff.write(_struct_6d.pack(_x.nunchuk_acceleration_zeroed.x, _x.nunchuk_acceleration_zeroed.y, _x.nunchuk_acceleration_zeroed.z, _x.nunchuk_acceleration_raw.x, _x.nunchuk_acceleration_raw.y, _x.nunchuk_acceleration_raw.z))
00347 buff.write(_struct_2f.pack(*self.nunchuk_joystick_zeroed))
00348 buff.write(_struct_2f.pack(*self.nunchuk_joystick_raw))
00349 buff.write(_struct_11B.pack(*self.buttons))
00350 buff.write(_struct_2B.pack(*self.nunchuk_buttons))
00351 buff.write(_struct_4B.pack(*self.LEDs))
00352 buff.write(_struct_B.pack(self.rumble))
00353 length = len(self.ir_tracking)
00354 buff.write(_struct_I.pack(length))
00355 for val1 in self.ir_tracking:
00356 _x = val1
00357 buff.write(_struct_2dq.pack(_x.x, _x.y, _x.ir_size))
00358 _x = self
00359 buff.write(_struct_2f2IQ.pack(_x.raw_battery, _x.percent_battery, _x.zeroing_time.secs, _x.zeroing_time.nsecs, _x.errors))
00360 except struct.error as se: self._check_types(se)
00361 except TypeError as te: self._check_types(te)
00362
00363 def deserialize(self, str):
00364 """
00365 unpack serialized message in str into this message instance
00366 :param str: byte array of serialized message, ``str``
00367 """
00368 try:
00369 if self.header is None:
00370 self.header = std_msgs.msg.Header()
00371 if self.angular_velocity_zeroed is None:
00372 self.angular_velocity_zeroed = geometry_msgs.msg.Vector3()
00373 if self.angular_velocity_raw is None:
00374 self.angular_velocity_raw = geometry_msgs.msg.Vector3()
00375 if self.linear_acceleration_zeroed is None:
00376 self.linear_acceleration_zeroed = geometry_msgs.msg.Vector3()
00377 if self.linear_acceleration_raw is None:
00378 self.linear_acceleration_raw = geometry_msgs.msg.Vector3()
00379 if self.nunchuk_acceleration_zeroed is None:
00380 self.nunchuk_acceleration_zeroed = geometry_msgs.msg.Vector3()
00381 if self.nunchuk_acceleration_raw is None:
00382 self.nunchuk_acceleration_raw = geometry_msgs.msg.Vector3()
00383 if self.ir_tracking is None:
00384 self.ir_tracking = None
00385 if self.zeroing_time is None:
00386 self.zeroing_time = genpy.Time()
00387 end = 0
00388 _x = self
00389 start = end
00390 end += 12
00391 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00392 start = end
00393 end += 4
00394 (length,) = _struct_I.unpack(str[start:end])
00395 start = end
00396 end += length
00397 if python3:
00398 self.header.frame_id = str[start:end].decode('utf-8')
00399 else:
00400 self.header.frame_id = str[start:end]
00401 _x = self
00402 start = end
00403 end += 48
00404 (_x.angular_velocity_zeroed.x, _x.angular_velocity_zeroed.y, _x.angular_velocity_zeroed.z, _x.angular_velocity_raw.x, _x.angular_velocity_raw.y, _x.angular_velocity_raw.z,) = _struct_6d.unpack(str[start:end])
00405 start = end
00406 end += 72
00407 self.angular_velocity_covariance = _struct_9d.unpack(str[start:end])
00408 _x = self
00409 start = end
00410 end += 48
00411 (_x.linear_acceleration_zeroed.x, _x.linear_acceleration_zeroed.y, _x.linear_acceleration_zeroed.z, _x.linear_acceleration_raw.x, _x.linear_acceleration_raw.y, _x.linear_acceleration_raw.z,) = _struct_6d.unpack(str[start:end])
00412 start = end
00413 end += 72
00414 self.linear_acceleration_covariance = _struct_9d.unpack(str[start:end])
00415 _x = self
00416 start = end
00417 end += 48
00418 (_x.nunchuk_acceleration_zeroed.x, _x.nunchuk_acceleration_zeroed.y, _x.nunchuk_acceleration_zeroed.z, _x.nunchuk_acceleration_raw.x, _x.nunchuk_acceleration_raw.y, _x.nunchuk_acceleration_raw.z,) = _struct_6d.unpack(str[start:end])
00419 start = end
00420 end += 8
00421 self.nunchuk_joystick_zeroed = _struct_2f.unpack(str[start:end])
00422 start = end
00423 end += 8
00424 self.nunchuk_joystick_raw = _struct_2f.unpack(str[start:end])
00425 start = end
00426 end += 11
00427 self.buttons = _struct_11B.unpack(str[start:end])
00428 self.buttons = map(bool, self.buttons)
00429 start = end
00430 end += 2
00431 self.nunchuk_buttons = _struct_2B.unpack(str[start:end])
00432 self.nunchuk_buttons = map(bool, self.nunchuk_buttons)
00433 start = end
00434 end += 4
00435 self.LEDs = _struct_4B.unpack(str[start:end])
00436 self.LEDs = map(bool, self.LEDs)
00437 start = end
00438 end += 1
00439 (self.rumble,) = _struct_B.unpack(str[start:end])
00440 self.rumble = bool(self.rumble)
00441 start = end
00442 end += 4
00443 (length,) = _struct_I.unpack(str[start:end])
00444 self.ir_tracking = []
00445 for i in range(0, length):
00446 val1 = wiimote.msg.IrSourceInfo()
00447 _x = val1
00448 start = end
00449 end += 24
00450 (_x.x, _x.y, _x.ir_size,) = _struct_2dq.unpack(str[start:end])
00451 self.ir_tracking.append(val1)
00452 _x = self
00453 start = end
00454 end += 24
00455 (_x.raw_battery, _x.percent_battery, _x.zeroing_time.secs, _x.zeroing_time.nsecs, _x.errors,) = _struct_2f2IQ.unpack(str[start:end])
00456 self.zeroing_time.canon()
00457 return self
00458 except struct.error as e:
00459 raise genpy.DeserializationError(e)
00460
00461
00462 def serialize_numpy(self, buff, numpy):
00463 """
00464 serialize message with numpy array types into buffer
00465 :param buff: buffer, ``StringIO``
00466 :param numpy: numpy python module
00467 """
00468 try:
00469 _x = self
00470 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00471 _x = self.header.frame_id
00472 length = len(_x)
00473 if python3 or type(_x) == unicode:
00474 _x = _x.encode('utf-8')
00475 length = len(_x)
00476 buff.write(struct.pack('<I%ss'%length, length, _x))
00477 _x = self
00478 buff.write(_struct_6d.pack(_x.angular_velocity_zeroed.x, _x.angular_velocity_zeroed.y, _x.angular_velocity_zeroed.z, _x.angular_velocity_raw.x, _x.angular_velocity_raw.y, _x.angular_velocity_raw.z))
00479 buff.write(self.angular_velocity_covariance.tostring())
00480 _x = self
00481 buff.write(_struct_6d.pack(_x.linear_acceleration_zeroed.x, _x.linear_acceleration_zeroed.y, _x.linear_acceleration_zeroed.z, _x.linear_acceleration_raw.x, _x.linear_acceleration_raw.y, _x.linear_acceleration_raw.z))
00482 buff.write(self.linear_acceleration_covariance.tostring())
00483 _x = self
00484 buff.write(_struct_6d.pack(_x.nunchuk_acceleration_zeroed.x, _x.nunchuk_acceleration_zeroed.y, _x.nunchuk_acceleration_zeroed.z, _x.nunchuk_acceleration_raw.x, _x.nunchuk_acceleration_raw.y, _x.nunchuk_acceleration_raw.z))
00485 buff.write(self.nunchuk_joystick_zeroed.tostring())
00486 buff.write(self.nunchuk_joystick_raw.tostring())
00487 buff.write(self.buttons.tostring())
00488 buff.write(self.nunchuk_buttons.tostring())
00489 buff.write(self.LEDs.tostring())
00490 buff.write(_struct_B.pack(self.rumble))
00491 length = len(self.ir_tracking)
00492 buff.write(_struct_I.pack(length))
00493 for val1 in self.ir_tracking:
00494 _x = val1
00495 buff.write(_struct_2dq.pack(_x.x, _x.y, _x.ir_size))
00496 _x = self
00497 buff.write(_struct_2f2IQ.pack(_x.raw_battery, _x.percent_battery, _x.zeroing_time.secs, _x.zeroing_time.nsecs, _x.errors))
00498 except struct.error as se: self._check_types(se)
00499 except TypeError as te: self._check_types(te)
00500
00501 def deserialize_numpy(self, str, numpy):
00502 """
00503 unpack serialized message in str into this message instance using numpy for array types
00504 :param str: byte array of serialized message, ``str``
00505 :param numpy: numpy python module
00506 """
00507 try:
00508 if self.header is None:
00509 self.header = std_msgs.msg.Header()
00510 if self.angular_velocity_zeroed is None:
00511 self.angular_velocity_zeroed = geometry_msgs.msg.Vector3()
00512 if self.angular_velocity_raw is None:
00513 self.angular_velocity_raw = geometry_msgs.msg.Vector3()
00514 if self.linear_acceleration_zeroed is None:
00515 self.linear_acceleration_zeroed = geometry_msgs.msg.Vector3()
00516 if self.linear_acceleration_raw is None:
00517 self.linear_acceleration_raw = geometry_msgs.msg.Vector3()
00518 if self.nunchuk_acceleration_zeroed is None:
00519 self.nunchuk_acceleration_zeroed = geometry_msgs.msg.Vector3()
00520 if self.nunchuk_acceleration_raw is None:
00521 self.nunchuk_acceleration_raw = geometry_msgs.msg.Vector3()
00522 if self.ir_tracking is None:
00523 self.ir_tracking = None
00524 if self.zeroing_time is None:
00525 self.zeroing_time = genpy.Time()
00526 end = 0
00527 _x = self
00528 start = end
00529 end += 12
00530 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00531 start = end
00532 end += 4
00533 (length,) = _struct_I.unpack(str[start:end])
00534 start = end
00535 end += length
00536 if python3:
00537 self.header.frame_id = str[start:end].decode('utf-8')
00538 else:
00539 self.header.frame_id = str[start:end]
00540 _x = self
00541 start = end
00542 end += 48
00543 (_x.angular_velocity_zeroed.x, _x.angular_velocity_zeroed.y, _x.angular_velocity_zeroed.z, _x.angular_velocity_raw.x, _x.angular_velocity_raw.y, _x.angular_velocity_raw.z,) = _struct_6d.unpack(str[start:end])
00544 start = end
00545 end += 72
00546 self.angular_velocity_covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00547 _x = self
00548 start = end
00549 end += 48
00550 (_x.linear_acceleration_zeroed.x, _x.linear_acceleration_zeroed.y, _x.linear_acceleration_zeroed.z, _x.linear_acceleration_raw.x, _x.linear_acceleration_raw.y, _x.linear_acceleration_raw.z,) = _struct_6d.unpack(str[start:end])
00551 start = end
00552 end += 72
00553 self.linear_acceleration_covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00554 _x = self
00555 start = end
00556 end += 48
00557 (_x.nunchuk_acceleration_zeroed.x, _x.nunchuk_acceleration_zeroed.y, _x.nunchuk_acceleration_zeroed.z, _x.nunchuk_acceleration_raw.x, _x.nunchuk_acceleration_raw.y, _x.nunchuk_acceleration_raw.z,) = _struct_6d.unpack(str[start:end])
00558 start = end
00559 end += 8
00560 self.nunchuk_joystick_zeroed = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=2)
00561 start = end
00562 end += 8
00563 self.nunchuk_joystick_raw = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=2)
00564 start = end
00565 end += 11
00566 self.buttons = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=11)
00567 self.buttons = map(bool, self.buttons)
00568 start = end
00569 end += 2
00570 self.nunchuk_buttons = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=2)
00571 self.nunchuk_buttons = map(bool, self.nunchuk_buttons)
00572 start = end
00573 end += 4
00574 self.LEDs = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=4)
00575 self.LEDs = map(bool, self.LEDs)
00576 start = end
00577 end += 1
00578 (self.rumble,) = _struct_B.unpack(str[start:end])
00579 self.rumble = bool(self.rumble)
00580 start = end
00581 end += 4
00582 (length,) = _struct_I.unpack(str[start:end])
00583 self.ir_tracking = []
00584 for i in range(0, length):
00585 val1 = wiimote.msg.IrSourceInfo()
00586 _x = val1
00587 start = end
00588 end += 24
00589 (_x.x, _x.y, _x.ir_size,) = _struct_2dq.unpack(str[start:end])
00590 self.ir_tracking.append(val1)
00591 _x = self
00592 start = end
00593 end += 24
00594 (_x.raw_battery, _x.percent_battery, _x.zeroing_time.secs, _x.zeroing_time.nsecs, _x.errors,) = _struct_2f2IQ.unpack(str[start:end])
00595 self.zeroing_time.canon()
00596 return self
00597 except struct.error as e:
00598 raise genpy.DeserializationError(e)
00599
00600 _struct_I = genpy.struct_I
00601 _struct_B = struct.Struct("<B")
00602 _struct_6d = struct.Struct("<6d")
00603 _struct_11B = struct.Struct("<11B")
00604 _struct_9d = struct.Struct("<9d")
00605 _struct_3I = struct.Struct("<3I")
00606 _struct_2f = struct.Struct("<2f")
00607 _struct_2B = struct.Struct("<2B")
00608 _struct_2f2IQ = struct.Struct("<2f2IQ")
00609 _struct_2dq = struct.Struct("<2dq")
00610 _struct_4B = struct.Struct("<4B")