_CartesianPose.py
Go to the documentation of this file.
00001 """autogenerated by genpy from brics_actuator/CartesianPose.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 brics_actuator.msg
00008 import geometry_msgs.msg
00009 import genpy
00010 
00011 class CartesianPose(genpy.Message):
00012   _md5sum = "0fe287468091771914ed98dea2d2a5a5"
00013   _type = "brics_actuator/CartesianPose"
00014   _has_header = False #flag to mark the presence of a Header object
00015   _full_text = """time timeStamp
00016 Poison poisonStamp
00017 string base_frame_uri
00018 string target_frame_uri
00019 CartesianVector position
00020 geometry_msgs/Quaternion orientation
00021 
00022 ================================================================================
00023 MSG: brics_actuator/Poison
00024 string originator               # node id
00025 string description              # encoding still an issue
00026 float32 qos                     # reliability of the channel
00027                                 # 0..1 where 1 means healthy
00028 
00029 ================================================================================
00030 MSG: brics_actuator/CartesianVector
00031 string unit
00032 float64 x
00033 float64 y
00034 float64 z
00035 
00036 ================================================================================
00037 MSG: geometry_msgs/Quaternion
00038 # This represents an orientation in free space in quaternion form.
00039 
00040 float64 x
00041 float64 y
00042 float64 z
00043 float64 w
00044 
00045 """
00046   __slots__ = ['timeStamp','poisonStamp','base_frame_uri','target_frame_uri','position','orientation']
00047   _slot_types = ['time','brics_actuator/Poison','string','string','brics_actuator/CartesianVector','geometry_msgs/Quaternion']
00048 
00049   def __init__(self, *args, **kwds):
00050     """
00051     Constructor. Any message fields that are implicitly/explicitly
00052     set to None will be assigned a default value. The recommend
00053     use is keyword arguments as this is more robust to future message
00054     changes.  You cannot mix in-order arguments and keyword arguments.
00055 
00056     The available fields are:
00057        timeStamp,poisonStamp,base_frame_uri,target_frame_uri,position,orientation
00058 
00059     :param args: complete set of field values, in .msg order
00060     :param kwds: use keyword arguments corresponding to message field names
00061     to set specific fields.
00062     """
00063     if args or kwds:
00064       super(CartesianPose, self).__init__(*args, **kwds)
00065       #message fields cannot be None, assign default values for those that are
00066       if self.timeStamp is None:
00067         self.timeStamp = genpy.Time()
00068       if self.poisonStamp is None:
00069         self.poisonStamp = brics_actuator.msg.Poison()
00070       if self.base_frame_uri is None:
00071         self.base_frame_uri = ''
00072       if self.target_frame_uri is None:
00073         self.target_frame_uri = ''
00074       if self.position is None:
00075         self.position = brics_actuator.msg.CartesianVector()
00076       if self.orientation is None:
00077         self.orientation = geometry_msgs.msg.Quaternion()
00078     else:
00079       self.timeStamp = genpy.Time()
00080       self.poisonStamp = brics_actuator.msg.Poison()
00081       self.base_frame_uri = ''
00082       self.target_frame_uri = ''
00083       self.position = brics_actuator.msg.CartesianVector()
00084       self.orientation = geometry_msgs.msg.Quaternion()
00085 
00086   def _get_types(self):
00087     """
00088     internal API method
00089     """
00090     return self._slot_types
00091 
00092   def serialize(self, buff):
00093     """
00094     serialize message into buffer
00095     :param buff: buffer, ``StringIO``
00096     """
00097     try:
00098       _x = self
00099       buff.write(_struct_2I.pack(_x.timeStamp.secs, _x.timeStamp.nsecs))
00100       _x = self.poisonStamp.originator
00101       length = len(_x)
00102       if python3 or type(_x) == unicode:
00103         _x = _x.encode('utf-8')
00104         length = len(_x)
00105       buff.write(struct.pack('<I%ss'%length, length, _x))
00106       _x = self.poisonStamp.description
00107       length = len(_x)
00108       if python3 or type(_x) == unicode:
00109         _x = _x.encode('utf-8')
00110         length = len(_x)
00111       buff.write(struct.pack('<I%ss'%length, length, _x))
00112       buff.write(_struct_f.pack(self.poisonStamp.qos))
00113       _x = self.base_frame_uri
00114       length = len(_x)
00115       if python3 or type(_x) == unicode:
00116         _x = _x.encode('utf-8')
00117         length = len(_x)
00118       buff.write(struct.pack('<I%ss'%length, length, _x))
00119       _x = self.target_frame_uri
00120       length = len(_x)
00121       if python3 or type(_x) == unicode:
00122         _x = _x.encode('utf-8')
00123         length = len(_x)
00124       buff.write(struct.pack('<I%ss'%length, length, _x))
00125       _x = self.position.unit
00126       length = len(_x)
00127       if python3 or type(_x) == unicode:
00128         _x = _x.encode('utf-8')
00129         length = len(_x)
00130       buff.write(struct.pack('<I%ss'%length, length, _x))
00131       _x = self
00132       buff.write(_struct_7d.pack(_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w))
00133     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00134     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00135 
00136   def deserialize(self, str):
00137     """
00138     unpack serialized message in str into this message instance
00139     :param str: byte array of serialized message, ``str``
00140     """
00141     try:
00142       if self.timeStamp is None:
00143         self.timeStamp = genpy.Time()
00144       if self.poisonStamp is None:
00145         self.poisonStamp = brics_actuator.msg.Poison()
00146       if self.position is None:
00147         self.position = brics_actuator.msg.CartesianVector()
00148       if self.orientation is None:
00149         self.orientation = geometry_msgs.msg.Quaternion()
00150       end = 0
00151       _x = self
00152       start = end
00153       end += 8
00154       (_x.timeStamp.secs, _x.timeStamp.nsecs,) = _struct_2I.unpack(str[start:end])
00155       start = end
00156       end += 4
00157       (length,) = _struct_I.unpack(str[start:end])
00158       start = end
00159       end += length
00160       if python3:
00161         self.poisonStamp.originator = str[start:end].decode('utf-8')
00162       else:
00163         self.poisonStamp.originator = str[start:end]
00164       start = end
00165       end += 4
00166       (length,) = _struct_I.unpack(str[start:end])
00167       start = end
00168       end += length
00169       if python3:
00170         self.poisonStamp.description = str[start:end].decode('utf-8')
00171       else:
00172         self.poisonStamp.description = str[start:end]
00173       start = end
00174       end += 4
00175       (self.poisonStamp.qos,) = _struct_f.unpack(str[start:end])
00176       start = end
00177       end += 4
00178       (length,) = _struct_I.unpack(str[start:end])
00179       start = end
00180       end += length
00181       if python3:
00182         self.base_frame_uri = str[start:end].decode('utf-8')
00183       else:
00184         self.base_frame_uri = str[start:end]
00185       start = end
00186       end += 4
00187       (length,) = _struct_I.unpack(str[start:end])
00188       start = end
00189       end += length
00190       if python3:
00191         self.target_frame_uri = str[start:end].decode('utf-8')
00192       else:
00193         self.target_frame_uri = str[start:end]
00194       start = end
00195       end += 4
00196       (length,) = _struct_I.unpack(str[start:end])
00197       start = end
00198       end += length
00199       if python3:
00200         self.position.unit = str[start:end].decode('utf-8')
00201       else:
00202         self.position.unit = str[start:end]
00203       _x = self
00204       start = end
00205       end += 56
00206       (_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w,) = _struct_7d.unpack(str[start:end])
00207       self.timeStamp.canon()
00208       return self
00209     except struct.error as e:
00210       raise genpy.DeserializationError(e) #most likely buffer underfill
00211 
00212 
00213   def serialize_numpy(self, buff, numpy):
00214     """
00215     serialize message with numpy array types into buffer
00216     :param buff: buffer, ``StringIO``
00217     :param numpy: numpy python module
00218     """
00219     try:
00220       _x = self
00221       buff.write(_struct_2I.pack(_x.timeStamp.secs, _x.timeStamp.nsecs))
00222       _x = self.poisonStamp.originator
00223       length = len(_x)
00224       if python3 or type(_x) == unicode:
00225         _x = _x.encode('utf-8')
00226         length = len(_x)
00227       buff.write(struct.pack('<I%ss'%length, length, _x))
00228       _x = self.poisonStamp.description
00229       length = len(_x)
00230       if python3 or type(_x) == unicode:
00231         _x = _x.encode('utf-8')
00232         length = len(_x)
00233       buff.write(struct.pack('<I%ss'%length, length, _x))
00234       buff.write(_struct_f.pack(self.poisonStamp.qos))
00235       _x = self.base_frame_uri
00236       length = len(_x)
00237       if python3 or type(_x) == unicode:
00238         _x = _x.encode('utf-8')
00239         length = len(_x)
00240       buff.write(struct.pack('<I%ss'%length, length, _x))
00241       _x = self.target_frame_uri
00242       length = len(_x)
00243       if python3 or type(_x) == unicode:
00244         _x = _x.encode('utf-8')
00245         length = len(_x)
00246       buff.write(struct.pack('<I%ss'%length, length, _x))
00247       _x = self.position.unit
00248       length = len(_x)
00249       if python3 or type(_x) == unicode:
00250         _x = _x.encode('utf-8')
00251         length = len(_x)
00252       buff.write(struct.pack('<I%ss'%length, length, _x))
00253       _x = self
00254       buff.write(_struct_7d.pack(_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w))
00255     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00256     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00257 
00258   def deserialize_numpy(self, str, numpy):
00259     """
00260     unpack serialized message in str into this message instance using numpy for array types
00261     :param str: byte array of serialized message, ``str``
00262     :param numpy: numpy python module
00263     """
00264     try:
00265       if self.timeStamp is None:
00266         self.timeStamp = genpy.Time()
00267       if self.poisonStamp is None:
00268         self.poisonStamp = brics_actuator.msg.Poison()
00269       if self.position is None:
00270         self.position = brics_actuator.msg.CartesianVector()
00271       if self.orientation is None:
00272         self.orientation = geometry_msgs.msg.Quaternion()
00273       end = 0
00274       _x = self
00275       start = end
00276       end += 8
00277       (_x.timeStamp.secs, _x.timeStamp.nsecs,) = _struct_2I.unpack(str[start:end])
00278       start = end
00279       end += 4
00280       (length,) = _struct_I.unpack(str[start:end])
00281       start = end
00282       end += length
00283       if python3:
00284         self.poisonStamp.originator = str[start:end].decode('utf-8')
00285       else:
00286         self.poisonStamp.originator = str[start:end]
00287       start = end
00288       end += 4
00289       (length,) = _struct_I.unpack(str[start:end])
00290       start = end
00291       end += length
00292       if python3:
00293         self.poisonStamp.description = str[start:end].decode('utf-8')
00294       else:
00295         self.poisonStamp.description = str[start:end]
00296       start = end
00297       end += 4
00298       (self.poisonStamp.qos,) = _struct_f.unpack(str[start:end])
00299       start = end
00300       end += 4
00301       (length,) = _struct_I.unpack(str[start:end])
00302       start = end
00303       end += length
00304       if python3:
00305         self.base_frame_uri = str[start:end].decode('utf-8')
00306       else:
00307         self.base_frame_uri = str[start:end]
00308       start = end
00309       end += 4
00310       (length,) = _struct_I.unpack(str[start:end])
00311       start = end
00312       end += length
00313       if python3:
00314         self.target_frame_uri = str[start:end].decode('utf-8')
00315       else:
00316         self.target_frame_uri = str[start:end]
00317       start = end
00318       end += 4
00319       (length,) = _struct_I.unpack(str[start:end])
00320       start = end
00321       end += length
00322       if python3:
00323         self.position.unit = str[start:end].decode('utf-8')
00324       else:
00325         self.position.unit = str[start:end]
00326       _x = self
00327       start = end
00328       end += 56
00329       (_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w,) = _struct_7d.unpack(str[start:end])
00330       self.timeStamp.canon()
00331       return self
00332     except struct.error as e:
00333       raise genpy.DeserializationError(e) #most likely buffer underfill
00334 
00335 _struct_I = genpy.struct_I
00336 _struct_7d = struct.Struct("<7d")
00337 _struct_2I = struct.Struct("<2I")
00338 _struct_f = struct.Struct("<f")


brics_actuator
Author(s): Alexander Bubeck
autogenerated on Sun Oct 5 2014 22:58:19