_AggregatedPoseTwist.py
Go to the documentation of this file.
00001 """autogenerated by genpy from collvoid_msgs/AggregatedPoseTwist.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 geometry_msgs.msg
00008 import collvoid_msgs.msg
00009 import std_msgs.msg
00010 
00011 class AggregatedPoseTwist(genpy.Message):
00012   _md5sum = "b57a6e1f6dc93663d454cab62daa81a6"
00013   _type = "collvoid_msgs/AggregatedPoseTwist"
00014   _has_header = True #flag to mark the presence of a Header object
00015   _full_text = """Header header
00016 collvoid_msgs/PoseTwistWithCovariance[] posetwists
00017 ================================================================================
00018 MSG: std_msgs/Header
00019 # Standard metadata for higher-level stamped data types.
00020 # This is generally used to communicate timestamped data 
00021 # in a particular coordinate frame.
00022 # 
00023 # sequence ID: consecutively increasing ID 
00024 uint32 seq
00025 #Two-integer timestamp that is expressed as:
00026 # * stamp.secs: seconds (stamp_secs) since epoch
00027 # * stamp.nsecs: nanoseconds since stamp_secs
00028 # time-handling sugar is provided by the client library
00029 time stamp
00030 #Frame this data is associated with
00031 # 0: no frame
00032 # 1: global frame
00033 string frame_id
00034 
00035 ================================================================================
00036 MSG: collvoid_msgs/PoseTwistWithCovariance
00037 Header header
00038 string robot_id
00039 float32 radius
00040 bool holo_robot
00041 bool controlled
00042 geometry_msgs/Vector3 holonomic_velocity
00043 geometry_msgs/PoseWithCovariance pose
00044 geometry_msgs/TwistWithCovariance twist
00045 geometry_msgs/PolygonStamped footprint
00046 
00047 ================================================================================
00048 MSG: geometry_msgs/Vector3
00049 # This represents a vector in free space. 
00050 
00051 float64 x
00052 float64 y
00053 float64 z
00054 ================================================================================
00055 MSG: geometry_msgs/PoseWithCovariance
00056 # This represents a pose in free space with uncertainty.
00057 
00058 Pose pose
00059 
00060 # Row-major representation of the 6x6 covariance matrix
00061 # The orientation parameters use a fixed-axis representation.
00062 # In order, the parameters are:
00063 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
00064 float64[36] covariance
00065 
00066 ================================================================================
00067 MSG: geometry_msgs/Pose
00068 # A representation of pose in free space, composed of postion and orientation. 
00069 Point position
00070 Quaternion orientation
00071 
00072 ================================================================================
00073 MSG: geometry_msgs/Point
00074 # This contains the position of a point in free space
00075 float64 x
00076 float64 y
00077 float64 z
00078 
00079 ================================================================================
00080 MSG: geometry_msgs/Quaternion
00081 # This represents an orientation in free space in quaternion form.
00082 
00083 float64 x
00084 float64 y
00085 float64 z
00086 float64 w
00087 
00088 ================================================================================
00089 MSG: geometry_msgs/TwistWithCovariance
00090 # This expresses velocity in free space with uncertianty.
00091 
00092 Twist twist
00093 
00094 # Row-major representation of the 6x6 covariance matrix
00095 # The orientation parameters use a fixed-axis representation.
00096 # In order, the parameters are:
00097 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
00098 float64[36] covariance
00099 
00100 ================================================================================
00101 MSG: geometry_msgs/Twist
00102 # This expresses velocity in free space broken into it's linear and angular parts. 
00103 Vector3  linear
00104 Vector3  angular
00105 
00106 ================================================================================
00107 MSG: geometry_msgs/PolygonStamped
00108 # This represents a Polygon with reference coordinate frame and timestamp
00109 Header header
00110 Polygon polygon
00111 
00112 ================================================================================
00113 MSG: geometry_msgs/Polygon
00114 #A specification of a polygon where the first and last points are assumed to be connected
00115 Point32[] points
00116 
00117 ================================================================================
00118 MSG: geometry_msgs/Point32
00119 # This contains the position of a point in free space(with 32 bits of precision).
00120 # It is recommeded to use Point wherever possible instead of Point32.  
00121 # 
00122 # This recommendation is to promote interoperability.  
00123 #
00124 # This message is designed to take up less space when sending
00125 # lots of points at once, as in the case of a PointCloud.  
00126 
00127 float32 x
00128 float32 y
00129 float32 z
00130 """
00131   __slots__ = ['header','posetwists']
00132   _slot_types = ['std_msgs/Header','collvoid_msgs/PoseTwistWithCovariance[]']
00133 
00134   def __init__(self, *args, **kwds):
00135     """
00136     Constructor. Any message fields that are implicitly/explicitly
00137     set to None will be assigned a default value. The recommend
00138     use is keyword arguments as this is more robust to future message
00139     changes.  You cannot mix in-order arguments and keyword arguments.
00140 
00141     The available fields are:
00142        header,posetwists
00143 
00144     :param args: complete set of field values, in .msg order
00145     :param kwds: use keyword arguments corresponding to message field names
00146     to set specific fields.
00147     """
00148     if args or kwds:
00149       super(AggregatedPoseTwist, self).__init__(*args, **kwds)
00150       #message fields cannot be None, assign default values for those that are
00151       if self.header is None:
00152         self.header = std_msgs.msg.Header()
00153       if self.posetwists is None:
00154         self.posetwists = []
00155     else:
00156       self.header = std_msgs.msg.Header()
00157       self.posetwists = []
00158 
00159   def _get_types(self):
00160     """
00161     internal API method
00162     """
00163     return self._slot_types
00164 
00165   def serialize(self, buff):
00166     """
00167     serialize message into buffer
00168     :param buff: buffer, ``StringIO``
00169     """
00170     try:
00171       _x = self
00172       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00173       _x = self.header.frame_id
00174       length = len(_x)
00175       if python3 or type(_x) == unicode:
00176         _x = _x.encode('utf-8')
00177         length = len(_x)
00178       buff.write(struct.pack('<I%ss'%length, length, _x))
00179       length = len(self.posetwists)
00180       buff.write(_struct_I.pack(length))
00181       for val1 in self.posetwists:
00182         _v1 = val1.header
00183         buff.write(_struct_I.pack(_v1.seq))
00184         _v2 = _v1.stamp
00185         _x = _v2
00186         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00187         _x = _v1.frame_id
00188         length = len(_x)
00189         if python3 or type(_x) == unicode:
00190           _x = _x.encode('utf-8')
00191           length = len(_x)
00192         buff.write(struct.pack('<I%ss'%length, length, _x))
00193         _x = val1.robot_id
00194         length = len(_x)
00195         if python3 or type(_x) == unicode:
00196           _x = _x.encode('utf-8')
00197           length = len(_x)
00198         buff.write(struct.pack('<I%ss'%length, length, _x))
00199         _x = val1
00200         buff.write(_struct_f2B.pack(_x.radius, _x.holo_robot, _x.controlled))
00201         _v3 = val1.holonomic_velocity
00202         _x = _v3
00203         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00204         _v4 = val1.pose
00205         _v5 = _v4.pose
00206         _v6 = _v5.position
00207         _x = _v6
00208         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00209         _v7 = _v5.orientation
00210         _x = _v7
00211         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00212         buff.write(_struct_36d.pack(*_v4.covariance))
00213         _v8 = val1.twist
00214         _v9 = _v8.twist
00215         _v10 = _v9.linear
00216         _x = _v10
00217         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00218         _v11 = _v9.angular
00219         _x = _v11
00220         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00221         buff.write(_struct_36d.pack(*_v8.covariance))
00222         _v12 = val1.footprint
00223         _v13 = _v12.header
00224         buff.write(_struct_I.pack(_v13.seq))
00225         _v14 = _v13.stamp
00226         _x = _v14
00227         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00228         _x = _v13.frame_id
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         _v15 = _v12.polygon
00235         length = len(_v15.points)
00236         buff.write(_struct_I.pack(length))
00237         for val4 in _v15.points:
00238           _x = val4
00239           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00240     except struct.error as se: self._check_types(se)
00241     except TypeError as te: self._check_types(te)
00242 
00243   def deserialize(self, str):
00244     """
00245     unpack serialized message in str into this message instance
00246     :param str: byte array of serialized message, ``str``
00247     """
00248     try:
00249       if self.header is None:
00250         self.header = std_msgs.msg.Header()
00251       if self.posetwists is None:
00252         self.posetwists = None
00253       end = 0
00254       _x = self
00255       start = end
00256       end += 12
00257       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00258       start = end
00259       end += 4
00260       (length,) = _struct_I.unpack(str[start:end])
00261       start = end
00262       end += length
00263       if python3:
00264         self.header.frame_id = str[start:end].decode('utf-8')
00265       else:
00266         self.header.frame_id = str[start:end]
00267       start = end
00268       end += 4
00269       (length,) = _struct_I.unpack(str[start:end])
00270       self.posetwists = []
00271       for i in range(0, length):
00272         val1 = collvoid_msgs.msg.PoseTwistWithCovariance()
00273         _v16 = val1.header
00274         start = end
00275         end += 4
00276         (_v16.seq,) = _struct_I.unpack(str[start:end])
00277         _v17 = _v16.stamp
00278         _x = _v17
00279         start = end
00280         end += 8
00281         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00282         start = end
00283         end += 4
00284         (length,) = _struct_I.unpack(str[start:end])
00285         start = end
00286         end += length
00287         if python3:
00288           _v16.frame_id = str[start:end].decode('utf-8')
00289         else:
00290           _v16.frame_id = str[start:end]
00291         start = end
00292         end += 4
00293         (length,) = _struct_I.unpack(str[start:end])
00294         start = end
00295         end += length
00296         if python3:
00297           val1.robot_id = str[start:end].decode('utf-8')
00298         else:
00299           val1.robot_id = str[start:end]
00300         _x = val1
00301         start = end
00302         end += 6
00303         (_x.radius, _x.holo_robot, _x.controlled,) = _struct_f2B.unpack(str[start:end])
00304         val1.holo_robot = bool(val1.holo_robot)
00305         val1.controlled = bool(val1.controlled)
00306         _v18 = val1.holonomic_velocity
00307         _x = _v18
00308         start = end
00309         end += 24
00310         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00311         _v19 = val1.pose
00312         _v20 = _v19.pose
00313         _v21 = _v20.position
00314         _x = _v21
00315         start = end
00316         end += 24
00317         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00318         _v22 = _v20.orientation
00319         _x = _v22
00320         start = end
00321         end += 32
00322         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00323         start = end
00324         end += 288
00325         _v19.covariance = _struct_36d.unpack(str[start:end])
00326         _v23 = val1.twist
00327         _v24 = _v23.twist
00328         _v25 = _v24.linear
00329         _x = _v25
00330         start = end
00331         end += 24
00332         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00333         _v26 = _v24.angular
00334         _x = _v26
00335         start = end
00336         end += 24
00337         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00338         start = end
00339         end += 288
00340         _v23.covariance = _struct_36d.unpack(str[start:end])
00341         _v27 = val1.footprint
00342         _v28 = _v27.header
00343         start = end
00344         end += 4
00345         (_v28.seq,) = _struct_I.unpack(str[start:end])
00346         _v29 = _v28.stamp
00347         _x = _v29
00348         start = end
00349         end += 8
00350         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00351         start = end
00352         end += 4
00353         (length,) = _struct_I.unpack(str[start:end])
00354         start = end
00355         end += length
00356         if python3:
00357           _v28.frame_id = str[start:end].decode('utf-8')
00358         else:
00359           _v28.frame_id = str[start:end]
00360         _v30 = _v27.polygon
00361         start = end
00362         end += 4
00363         (length,) = _struct_I.unpack(str[start:end])
00364         _v30.points = []
00365         for i in range(0, length):
00366           val4 = geometry_msgs.msg.Point32()
00367           _x = val4
00368           start = end
00369           end += 12
00370           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00371           _v30.points.append(val4)
00372         self.posetwists.append(val1)
00373       return self
00374     except struct.error as e:
00375       raise genpy.DeserializationError(e) #most likely buffer underfill
00376 
00377 
00378   def serialize_numpy(self, buff, numpy):
00379     """
00380     serialize message with numpy array types into buffer
00381     :param buff: buffer, ``StringIO``
00382     :param numpy: numpy python module
00383     """
00384     try:
00385       _x = self
00386       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00387       _x = self.header.frame_id
00388       length = len(_x)
00389       if python3 or type(_x) == unicode:
00390         _x = _x.encode('utf-8')
00391         length = len(_x)
00392       buff.write(struct.pack('<I%ss'%length, length, _x))
00393       length = len(self.posetwists)
00394       buff.write(_struct_I.pack(length))
00395       for val1 in self.posetwists:
00396         _v31 = val1.header
00397         buff.write(_struct_I.pack(_v31.seq))
00398         _v32 = _v31.stamp
00399         _x = _v32
00400         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00401         _x = _v31.frame_id
00402         length = len(_x)
00403         if python3 or type(_x) == unicode:
00404           _x = _x.encode('utf-8')
00405           length = len(_x)
00406         buff.write(struct.pack('<I%ss'%length, length, _x))
00407         _x = val1.robot_id
00408         length = len(_x)
00409         if python3 or type(_x) == unicode:
00410           _x = _x.encode('utf-8')
00411           length = len(_x)
00412         buff.write(struct.pack('<I%ss'%length, length, _x))
00413         _x = val1
00414         buff.write(_struct_f2B.pack(_x.radius, _x.holo_robot, _x.controlled))
00415         _v33 = val1.holonomic_velocity
00416         _x = _v33
00417         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00418         _v34 = val1.pose
00419         _v35 = _v34.pose
00420         _v36 = _v35.position
00421         _x = _v36
00422         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00423         _v37 = _v35.orientation
00424         _x = _v37
00425         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00426         buff.write(_v34.covariance.tostring())
00427         _v38 = val1.twist
00428         _v39 = _v38.twist
00429         _v40 = _v39.linear
00430         _x = _v40
00431         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00432         _v41 = _v39.angular
00433         _x = _v41
00434         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00435         buff.write(_v38.covariance.tostring())
00436         _v42 = val1.footprint
00437         _v43 = _v42.header
00438         buff.write(_struct_I.pack(_v43.seq))
00439         _v44 = _v43.stamp
00440         _x = _v44
00441         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00442         _x = _v43.frame_id
00443         length = len(_x)
00444         if python3 or type(_x) == unicode:
00445           _x = _x.encode('utf-8')
00446           length = len(_x)
00447         buff.write(struct.pack('<I%ss'%length, length, _x))
00448         _v45 = _v42.polygon
00449         length = len(_v45.points)
00450         buff.write(_struct_I.pack(length))
00451         for val4 in _v45.points:
00452           _x = val4
00453           buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00454     except struct.error as se: self._check_types(se)
00455     except TypeError as te: self._check_types(te)
00456 
00457   def deserialize_numpy(self, str, numpy):
00458     """
00459     unpack serialized message in str into this message instance using numpy for array types
00460     :param str: byte array of serialized message, ``str``
00461     :param numpy: numpy python module
00462     """
00463     try:
00464       if self.header is None:
00465         self.header = std_msgs.msg.Header()
00466       if self.posetwists is None:
00467         self.posetwists = None
00468       end = 0
00469       _x = self
00470       start = end
00471       end += 12
00472       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00473       start = end
00474       end += 4
00475       (length,) = _struct_I.unpack(str[start:end])
00476       start = end
00477       end += length
00478       if python3:
00479         self.header.frame_id = str[start:end].decode('utf-8')
00480       else:
00481         self.header.frame_id = str[start:end]
00482       start = end
00483       end += 4
00484       (length,) = _struct_I.unpack(str[start:end])
00485       self.posetwists = []
00486       for i in range(0, length):
00487         val1 = collvoid_msgs.msg.PoseTwistWithCovariance()
00488         _v46 = val1.header
00489         start = end
00490         end += 4
00491         (_v46.seq,) = _struct_I.unpack(str[start:end])
00492         _v47 = _v46.stamp
00493         _x = _v47
00494         start = end
00495         end += 8
00496         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00497         start = end
00498         end += 4
00499         (length,) = _struct_I.unpack(str[start:end])
00500         start = end
00501         end += length
00502         if python3:
00503           _v46.frame_id = str[start:end].decode('utf-8')
00504         else:
00505           _v46.frame_id = str[start:end]
00506         start = end
00507         end += 4
00508         (length,) = _struct_I.unpack(str[start:end])
00509         start = end
00510         end += length
00511         if python3:
00512           val1.robot_id = str[start:end].decode('utf-8')
00513         else:
00514           val1.robot_id = str[start:end]
00515         _x = val1
00516         start = end
00517         end += 6
00518         (_x.radius, _x.holo_robot, _x.controlled,) = _struct_f2B.unpack(str[start:end])
00519         val1.holo_robot = bool(val1.holo_robot)
00520         val1.controlled = bool(val1.controlled)
00521         _v48 = val1.holonomic_velocity
00522         _x = _v48
00523         start = end
00524         end += 24
00525         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00526         _v49 = val1.pose
00527         _v50 = _v49.pose
00528         _v51 = _v50.position
00529         _x = _v51
00530         start = end
00531         end += 24
00532         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00533         _v52 = _v50.orientation
00534         _x = _v52
00535         start = end
00536         end += 32
00537         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00538         start = end
00539         end += 288
00540         _v49.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00541         _v53 = val1.twist
00542         _v54 = _v53.twist
00543         _v55 = _v54.linear
00544         _x = _v55
00545         start = end
00546         end += 24
00547         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00548         _v56 = _v54.angular
00549         _x = _v56
00550         start = end
00551         end += 24
00552         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00553         start = end
00554         end += 288
00555         _v53.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00556         _v57 = val1.footprint
00557         _v58 = _v57.header
00558         start = end
00559         end += 4
00560         (_v58.seq,) = _struct_I.unpack(str[start:end])
00561         _v59 = _v58.stamp
00562         _x = _v59
00563         start = end
00564         end += 8
00565         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00566         start = end
00567         end += 4
00568         (length,) = _struct_I.unpack(str[start:end])
00569         start = end
00570         end += length
00571         if python3:
00572           _v58.frame_id = str[start:end].decode('utf-8')
00573         else:
00574           _v58.frame_id = str[start:end]
00575         _v60 = _v57.polygon
00576         start = end
00577         end += 4
00578         (length,) = _struct_I.unpack(str[start:end])
00579         _v60.points = []
00580         for i in range(0, length):
00581           val4 = geometry_msgs.msg.Point32()
00582           _x = val4
00583           start = end
00584           end += 12
00585           (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00586           _v60.points.append(val4)
00587         self.posetwists.append(val1)
00588       return self
00589     except struct.error as e:
00590       raise genpy.DeserializationError(e) #most likely buffer underfill
00591 
00592 _struct_I = genpy.struct_I
00593 _struct_f2B = struct.Struct("<f2B")
00594 _struct_36d = struct.Struct("<36d")
00595 _struct_3f = struct.Struct("<3f")
00596 _struct_3I = struct.Struct("<3I")
00597 _struct_4d = struct.Struct("<4d")
00598 _struct_2I = struct.Struct("<2I")
00599 _struct_3d = struct.Struct("<3d")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


collvoid_msgs
Author(s): Daniel Claes
autogenerated on Sun Aug 25 2013 10:10:17