_Tablet.py
Go to the documentation of this file.
00001 """autogenerated by genpy from jsk_gui_msgs/Tablet.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 jsk_gui_msgs.msg
00008 import std_msgs.msg
00009 
00010 class Tablet(genpy.Message):
00011   _md5sum = "0bab196c7b214826d8c27d7bd5f924f6"
00012   _type = "jsk_gui_msgs/Tablet"
00013   _has_header = True #flag to mark the presence of a Header object
00014   _full_text = """Header header
00015 # hardware_namel: iPad, Android, other mobile
00016 string hardware_name
00017 string hardware_id
00018 Action action
00019 DeviceSensor sensor
00020 Touch[] touches
00021 ================================================================================
00022 MSG: std_msgs/Header
00023 # Standard metadata for higher-level stamped data types.
00024 # This is generally used to communicate timestamped data 
00025 # in a particular coordinate frame.
00026 # 
00027 # sequence ID: consecutively increasing ID 
00028 uint32 seq
00029 #Two-integer timestamp that is expressed as:
00030 # * stamp.secs: seconds (stamp_secs) since epoch
00031 # * stamp.nsecs: nanoseconds since stamp_secs
00032 # time-handling sugar is provided by the client library
00033 time stamp
00034 #Frame this data is associated with
00035 # 0: no frame
00036 # 1: global frame
00037 string frame_id
00038 
00039 ================================================================================
00040 MSG: jsk_gui_msgs/Action
00041 byte RARMID=0
00042 byte LARMID=1
00043 
00044 # task: push, pick, open, slide, MoveNeck, MoveBase
00045 string task_name
00046 
00047 # selection: button names
00048 # string selection_name
00049 
00050 # arm: :rarm, :lsrm
00051 int64 arm_id
00052 
00053 # state of touch: touch, pick, pinch, sweep
00054 # for debugging
00055 string state
00056 # value of state
00057 float64 state_value
00058 
00059 # direction: up, down, left, right
00060 string direction
00061 # value of direction, degree
00062 float64 direction_value
00063 
00064 int64 touch_x
00065 int64 touch_y
00066 
00067 # Example
00068 #  push: touches[0].x, touches[0].y, task_name, arm_id
00069 #  open: touches[0 1 2].x, touches[0 1 2].y, task_name, arm_id
00070 #  slide: touches[0 1 2].x, touches[0 1 2].y, task_name, arm_id
00071 #  move_neck: task_name, direction, direction_value
00072 #  move_base: task_name, direction, direction_value
00073 ================================================================================
00074 MSG: jsk_gui_msgs/DeviceSensor
00075 float64 temperature
00076 float64 relative_humidity
00077 float64 light
00078 float64 pressure
00079 float64 proximity
00080 
00081 
00082 
00083 
00084 ================================================================================
00085 MSG: jsk_gui_msgs/Touch
00086 # finger_id
00087 int64 finger_id
00088 # touch point(screen point)
00089 float64 x
00090 float64 y
00091 # based image size (usually not needed)
00092 int64 image_width
00093 int64 image_height
00094 """
00095   __slots__ = ['header','hardware_name','hardware_id','action','sensor','touches']
00096   _slot_types = ['std_msgs/Header','string','string','jsk_gui_msgs/Action','jsk_gui_msgs/DeviceSensor','jsk_gui_msgs/Touch[]']
00097 
00098   def __init__(self, *args, **kwds):
00099     """
00100     Constructor. Any message fields that are implicitly/explicitly
00101     set to None will be assigned a default value. The recommend
00102     use is keyword arguments as this is more robust to future message
00103     changes.  You cannot mix in-order arguments and keyword arguments.
00104 
00105     The available fields are:
00106        header,hardware_name,hardware_id,action,sensor,touches
00107 
00108     :param args: complete set of field values, in .msg order
00109     :param kwds: use keyword arguments corresponding to message field names
00110     to set specific fields.
00111     """
00112     if args or kwds:
00113       super(Tablet, self).__init__(*args, **kwds)
00114       #message fields cannot be None, assign default values for those that are
00115       if self.header is None:
00116         self.header = std_msgs.msg.Header()
00117       if self.hardware_name is None:
00118         self.hardware_name = ''
00119       if self.hardware_id is None:
00120         self.hardware_id = ''
00121       if self.action is None:
00122         self.action = jsk_gui_msgs.msg.Action()
00123       if self.sensor is None:
00124         self.sensor = jsk_gui_msgs.msg.DeviceSensor()
00125       if self.touches is None:
00126         self.touches = []
00127     else:
00128       self.header = std_msgs.msg.Header()
00129       self.hardware_name = ''
00130       self.hardware_id = ''
00131       self.action = jsk_gui_msgs.msg.Action()
00132       self.sensor = jsk_gui_msgs.msg.DeviceSensor()
00133       self.touches = []
00134 
00135   def _get_types(self):
00136     """
00137     internal API method
00138     """
00139     return self._slot_types
00140 
00141   def serialize(self, buff):
00142     """
00143     serialize message into buffer
00144     :param buff: buffer, ``StringIO``
00145     """
00146     try:
00147       _x = self
00148       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00149       _x = self.header.frame_id
00150       length = len(_x)
00151       if python3 or type(_x) == unicode:
00152         _x = _x.encode('utf-8')
00153         length = len(_x)
00154       buff.write(struct.pack('<I%ss'%length, length, _x))
00155       _x = self.hardware_name
00156       length = len(_x)
00157       if python3 or type(_x) == unicode:
00158         _x = _x.encode('utf-8')
00159         length = len(_x)
00160       buff.write(struct.pack('<I%ss'%length, length, _x))
00161       _x = self.hardware_id
00162       length = len(_x)
00163       if python3 or type(_x) == unicode:
00164         _x = _x.encode('utf-8')
00165         length = len(_x)
00166       buff.write(struct.pack('<I%ss'%length, length, _x))
00167       _x = self.action.task_name
00168       length = len(_x)
00169       if python3 or type(_x) == unicode:
00170         _x = _x.encode('utf-8')
00171         length = len(_x)
00172       buff.write(struct.pack('<I%ss'%length, length, _x))
00173       buff.write(_struct_q.pack(self.action.arm_id))
00174       _x = self.action.state
00175       length = len(_x)
00176       if python3 or type(_x) == unicode:
00177         _x = _x.encode('utf-8')
00178         length = len(_x)
00179       buff.write(struct.pack('<I%ss'%length, length, _x))
00180       buff.write(_struct_d.pack(self.action.state_value))
00181       _x = self.action.direction
00182       length = len(_x)
00183       if python3 or type(_x) == unicode:
00184         _x = _x.encode('utf-8')
00185         length = len(_x)
00186       buff.write(struct.pack('<I%ss'%length, length, _x))
00187       _x = self
00188       buff.write(_struct_d2q5d.pack(_x.action.direction_value, _x.action.touch_x, _x.action.touch_y, _x.sensor.temperature, _x.sensor.relative_humidity, _x.sensor.light, _x.sensor.pressure, _x.sensor.proximity))
00189       length = len(self.touches)
00190       buff.write(_struct_I.pack(length))
00191       for val1 in self.touches:
00192         _x = val1
00193         buff.write(_struct_q2d2q.pack(_x.finger_id, _x.x, _x.y, _x.image_width, _x.image_height))
00194     except struct.error as se: self._check_types(se)
00195     except TypeError as te: self._check_types(te)
00196 
00197   def deserialize(self, str):
00198     """
00199     unpack serialized message in str into this message instance
00200     :param str: byte array of serialized message, ``str``
00201     """
00202     try:
00203       if self.header is None:
00204         self.header = std_msgs.msg.Header()
00205       if self.action is None:
00206         self.action = jsk_gui_msgs.msg.Action()
00207       if self.sensor is None:
00208         self.sensor = jsk_gui_msgs.msg.DeviceSensor()
00209       if self.touches is None:
00210         self.touches = None
00211       end = 0
00212       _x = self
00213       start = end
00214       end += 12
00215       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00216       start = end
00217       end += 4
00218       (length,) = _struct_I.unpack(str[start:end])
00219       start = end
00220       end += length
00221       if python3:
00222         self.header.frame_id = str[start:end].decode('utf-8')
00223       else:
00224         self.header.frame_id = str[start:end]
00225       start = end
00226       end += 4
00227       (length,) = _struct_I.unpack(str[start:end])
00228       start = end
00229       end += length
00230       if python3:
00231         self.hardware_name = str[start:end].decode('utf-8')
00232       else:
00233         self.hardware_name = str[start:end]
00234       start = end
00235       end += 4
00236       (length,) = _struct_I.unpack(str[start:end])
00237       start = end
00238       end += length
00239       if python3:
00240         self.hardware_id = str[start:end].decode('utf-8')
00241       else:
00242         self.hardware_id = str[start:end]
00243       start = end
00244       end += 4
00245       (length,) = _struct_I.unpack(str[start:end])
00246       start = end
00247       end += length
00248       if python3:
00249         self.action.task_name = str[start:end].decode('utf-8')
00250       else:
00251         self.action.task_name = str[start:end]
00252       start = end
00253       end += 8
00254       (self.action.arm_id,) = _struct_q.unpack(str[start:end])
00255       start = end
00256       end += 4
00257       (length,) = _struct_I.unpack(str[start:end])
00258       start = end
00259       end += length
00260       if python3:
00261         self.action.state = str[start:end].decode('utf-8')
00262       else:
00263         self.action.state = str[start:end]
00264       start = end
00265       end += 8
00266       (self.action.state_value,) = _struct_d.unpack(str[start:end])
00267       start = end
00268       end += 4
00269       (length,) = _struct_I.unpack(str[start:end])
00270       start = end
00271       end += length
00272       if python3:
00273         self.action.direction = str[start:end].decode('utf-8')
00274       else:
00275         self.action.direction = str[start:end]
00276       _x = self
00277       start = end
00278       end += 64
00279       (_x.action.direction_value, _x.action.touch_x, _x.action.touch_y, _x.sensor.temperature, _x.sensor.relative_humidity, _x.sensor.light, _x.sensor.pressure, _x.sensor.proximity,) = _struct_d2q5d.unpack(str[start:end])
00280       start = end
00281       end += 4
00282       (length,) = _struct_I.unpack(str[start:end])
00283       self.touches = []
00284       for i in range(0, length):
00285         val1 = jsk_gui_msgs.msg.Touch()
00286         _x = val1
00287         start = end
00288         end += 40
00289         (_x.finger_id, _x.x, _x.y, _x.image_width, _x.image_height,) = _struct_q2d2q.unpack(str[start:end])
00290         self.touches.append(val1)
00291       return self
00292     except struct.error as e:
00293       raise genpy.DeserializationError(e) #most likely buffer underfill
00294 
00295 
00296   def serialize_numpy(self, buff, numpy):
00297     """
00298     serialize message with numpy array types into buffer
00299     :param buff: buffer, ``StringIO``
00300     :param numpy: numpy python module
00301     """
00302     try:
00303       _x = self
00304       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00305       _x = self.header.frame_id
00306       length = len(_x)
00307       if python3 or type(_x) == unicode:
00308         _x = _x.encode('utf-8')
00309         length = len(_x)
00310       buff.write(struct.pack('<I%ss'%length, length, _x))
00311       _x = self.hardware_name
00312       length = len(_x)
00313       if python3 or type(_x) == unicode:
00314         _x = _x.encode('utf-8')
00315         length = len(_x)
00316       buff.write(struct.pack('<I%ss'%length, length, _x))
00317       _x = self.hardware_id
00318       length = len(_x)
00319       if python3 or type(_x) == unicode:
00320         _x = _x.encode('utf-8')
00321         length = len(_x)
00322       buff.write(struct.pack('<I%ss'%length, length, _x))
00323       _x = self.action.task_name
00324       length = len(_x)
00325       if python3 or type(_x) == unicode:
00326         _x = _x.encode('utf-8')
00327         length = len(_x)
00328       buff.write(struct.pack('<I%ss'%length, length, _x))
00329       buff.write(_struct_q.pack(self.action.arm_id))
00330       _x = self.action.state
00331       length = len(_x)
00332       if python3 or type(_x) == unicode:
00333         _x = _x.encode('utf-8')
00334         length = len(_x)
00335       buff.write(struct.pack('<I%ss'%length, length, _x))
00336       buff.write(_struct_d.pack(self.action.state_value))
00337       _x = self.action.direction
00338       length = len(_x)
00339       if python3 or type(_x) == unicode:
00340         _x = _x.encode('utf-8')
00341         length = len(_x)
00342       buff.write(struct.pack('<I%ss'%length, length, _x))
00343       _x = self
00344       buff.write(_struct_d2q5d.pack(_x.action.direction_value, _x.action.touch_x, _x.action.touch_y, _x.sensor.temperature, _x.sensor.relative_humidity, _x.sensor.light, _x.sensor.pressure, _x.sensor.proximity))
00345       length = len(self.touches)
00346       buff.write(_struct_I.pack(length))
00347       for val1 in self.touches:
00348         _x = val1
00349         buff.write(_struct_q2d2q.pack(_x.finger_id, _x.x, _x.y, _x.image_width, _x.image_height))
00350     except struct.error as se: self._check_types(se)
00351     except TypeError as te: self._check_types(te)
00352 
00353   def deserialize_numpy(self, str, numpy):
00354     """
00355     unpack serialized message in str into this message instance using numpy for array types
00356     :param str: byte array of serialized message, ``str``
00357     :param numpy: numpy python module
00358     """
00359     try:
00360       if self.header is None:
00361         self.header = std_msgs.msg.Header()
00362       if self.action is None:
00363         self.action = jsk_gui_msgs.msg.Action()
00364       if self.sensor is None:
00365         self.sensor = jsk_gui_msgs.msg.DeviceSensor()
00366       if self.touches is None:
00367         self.touches = None
00368       end = 0
00369       _x = self
00370       start = end
00371       end += 12
00372       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00373       start = end
00374       end += 4
00375       (length,) = _struct_I.unpack(str[start:end])
00376       start = end
00377       end += length
00378       if python3:
00379         self.header.frame_id = str[start:end].decode('utf-8')
00380       else:
00381         self.header.frame_id = str[start:end]
00382       start = end
00383       end += 4
00384       (length,) = _struct_I.unpack(str[start:end])
00385       start = end
00386       end += length
00387       if python3:
00388         self.hardware_name = str[start:end].decode('utf-8')
00389       else:
00390         self.hardware_name = str[start:end]
00391       start = end
00392       end += 4
00393       (length,) = _struct_I.unpack(str[start:end])
00394       start = end
00395       end += length
00396       if python3:
00397         self.hardware_id = str[start:end].decode('utf-8')
00398       else:
00399         self.hardware_id = str[start:end]
00400       start = end
00401       end += 4
00402       (length,) = _struct_I.unpack(str[start:end])
00403       start = end
00404       end += length
00405       if python3:
00406         self.action.task_name = str[start:end].decode('utf-8')
00407       else:
00408         self.action.task_name = str[start:end]
00409       start = end
00410       end += 8
00411       (self.action.arm_id,) = _struct_q.unpack(str[start:end])
00412       start = end
00413       end += 4
00414       (length,) = _struct_I.unpack(str[start:end])
00415       start = end
00416       end += length
00417       if python3:
00418         self.action.state = str[start:end].decode('utf-8')
00419       else:
00420         self.action.state = str[start:end]
00421       start = end
00422       end += 8
00423       (self.action.state_value,) = _struct_d.unpack(str[start:end])
00424       start = end
00425       end += 4
00426       (length,) = _struct_I.unpack(str[start:end])
00427       start = end
00428       end += length
00429       if python3:
00430         self.action.direction = str[start:end].decode('utf-8')
00431       else:
00432         self.action.direction = str[start:end]
00433       _x = self
00434       start = end
00435       end += 64
00436       (_x.action.direction_value, _x.action.touch_x, _x.action.touch_y, _x.sensor.temperature, _x.sensor.relative_humidity, _x.sensor.light, _x.sensor.pressure, _x.sensor.proximity,) = _struct_d2q5d.unpack(str[start:end])
00437       start = end
00438       end += 4
00439       (length,) = _struct_I.unpack(str[start:end])
00440       self.touches = []
00441       for i in range(0, length):
00442         val1 = jsk_gui_msgs.msg.Touch()
00443         _x = val1
00444         start = end
00445         end += 40
00446         (_x.finger_id, _x.x, _x.y, _x.image_width, _x.image_height,) = _struct_q2d2q.unpack(str[start:end])
00447         self.touches.append(val1)
00448       return self
00449     except struct.error as e:
00450       raise genpy.DeserializationError(e) #most likely buffer underfill
00451 
00452 _struct_I = genpy.struct_I
00453 _struct_q = struct.Struct("<q")
00454 _struct_q2d2q = struct.Struct("<q2d2q")
00455 _struct_3I = struct.Struct("<3I")
00456 _struct_d = struct.Struct("<d")
00457 _struct_d2q5d = struct.Struct("<d2q5d")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


jsk_gui_msgs
Author(s): chen
autogenerated on Sat Mar 23 2013 16:13:08