_TrackMsg.py
Go to the documentation of this file.
00001 """autogenerated by genpy from articulation_msgs/TrackMsg.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 sensor_msgs.msg
00008 import geometry_msgs.msg
00009 import std_msgs.msg
00010 
00011 class TrackMsg(genpy.Message):
00012   _md5sum = "f74375fd0f97f92e2767ab0a80c15590"
00013   _type = "articulation_msgs/TrackMsg"
00014   _has_header = True #flag to mark the presence of a Header object
00015   _full_text = """# Single kinematic trajectory
00016 #
00017 # This message contains a kinematic trajectory. The trajectory is specified
00018 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00019 # the track is valid, and whether it includes orientation. The track id
00020 # can be used for automatic coloring in the RVIZ track plugin, and can be 
00021 # freely chosen by the client. 
00022 #
00023 # A model is fitting only from the trajectory stored in the pose[]-vector. 
00024 # Additional information may be associated to each pose using the channels
00025 # vector, with arbitrary # fields (e.g., to include applied/measured forces). 
00026 #
00027 # After model evaluation,
00028 # also the associated configurations of the object are stored in the channels,
00029 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00030 # Model evaluation also projects the poses in the pose vector onto the model,
00031 # and stores these ideal poses in the vector pose_projected. Further, during model
00032 # evaluation, a new set of (uniform) configurations over the valid configuration
00033 # range is sampled, and the result is stored in pose_resampled.
00034 # The vector pose_flags contains additional display flags for the poses in the
00035 # pose vector, for example, whether a pose is visible and/or
00036 # the end of a trajectory segment. At the moment, this is only used by the
00037 # prior_model_learner.
00038 #
00039 
00040 std_msgs/Header header                        # frame and timestamp
00041 int32 id                                # used-specified track id
00042 
00043 geometry_msgs/Pose[] pose               # sequence of poses, defining the observed trajectory
00044 std_msgs/Header[] pose_headers                   # Timestamp and frame for each pose (and pose_projected)
00045 geometry_msgs/Pose[] pose_projected     # sequence of poses, projected to the model 
00046                                         # (after model evaluation)
00047 geometry_msgs/Pose[] pose_resampled     # sequence of poses, re-sampled from the model in
00048                                         # the valid configuration range
00049 uint32[] pose_flags                     # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00050 
00051 uint32 POSE_VISIBLE=1
00052 uint32 POSE_END_OF_SEGMENT=2
00053 
00054 # Each channel should have the same number of elements as pose array, 
00055 # and the data in each channel should correspond 1:1 with each pose
00056 # possible channels: "width", "height", "rgb", ...
00057 sensor_msgs/ChannelFloat32[] channels       
00058 
00059 
00060 
00061 ================================================================================
00062 MSG: std_msgs/Header
00063 # Standard metadata for higher-level stamped data types.
00064 # This is generally used to communicate timestamped data 
00065 # in a particular coordinate frame.
00066 # 
00067 # sequence ID: consecutively increasing ID 
00068 uint32 seq
00069 #Two-integer timestamp that is expressed as:
00070 # * stamp.secs: seconds (stamp_secs) since epoch
00071 # * stamp.nsecs: nanoseconds since stamp_secs
00072 # time-handling sugar is provided by the client library
00073 time stamp
00074 #Frame this data is associated with
00075 # 0: no frame
00076 # 1: global frame
00077 string frame_id
00078 
00079 ================================================================================
00080 MSG: geometry_msgs/Pose
00081 # A representation of pose in free space, composed of postion and orientation. 
00082 Point position
00083 Quaternion orientation
00084 
00085 ================================================================================
00086 MSG: geometry_msgs/Point
00087 # This contains the position of a point in free space
00088 float64 x
00089 float64 y
00090 float64 z
00091 
00092 ================================================================================
00093 MSG: geometry_msgs/Quaternion
00094 # This represents an orientation in free space in quaternion form.
00095 
00096 float64 x
00097 float64 y
00098 float64 z
00099 float64 w
00100 
00101 ================================================================================
00102 MSG: sensor_msgs/ChannelFloat32
00103 # This message is used by the PointCloud message to hold optional data
00104 # associated with each point in the cloud. The length of the values
00105 # array should be the same as the length of the points array in the
00106 # PointCloud, and each value should be associated with the corresponding
00107 # point.
00108 
00109 # Channel names in existing practice include:
00110 #   "u", "v" - row and column (respectively) in the left stereo image.
00111 #              This is opposite to usual conventions but remains for
00112 #              historical reasons. The newer PointCloud2 message has no
00113 #              such problem.
00114 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00115 #           (R,G,B) values packed into the least significant 24 bits,
00116 #           in order.
00117 #   "intensity" - laser or pixel intensity.
00118 #   "distance"
00119 
00120 # The channel name should give semantics of the channel (e.g.
00121 # "intensity" instead of "value").
00122 string name
00123 
00124 # The values array should be 1-1 with the elements of the associated
00125 # PointCloud.
00126 float32[] values
00127 
00128 """
00129   # Pseudo-constants
00130   POSE_VISIBLE = 1
00131   POSE_END_OF_SEGMENT = 2
00132 
00133   __slots__ = ['header','id','pose','pose_headers','pose_projected','pose_resampled','pose_flags','channels']
00134   _slot_types = ['std_msgs/Header','int32','geometry_msgs/Pose[]','std_msgs/Header[]','geometry_msgs/Pose[]','geometry_msgs/Pose[]','uint32[]','sensor_msgs/ChannelFloat32[]']
00135 
00136   def __init__(self, *args, **kwds):
00137     """
00138     Constructor. Any message fields that are implicitly/explicitly
00139     set to None will be assigned a default value. The recommend
00140     use is keyword arguments as this is more robust to future message
00141     changes.  You cannot mix in-order arguments and keyword arguments.
00142 
00143     The available fields are:
00144        header,id,pose,pose_headers,pose_projected,pose_resampled,pose_flags,channels
00145 
00146     :param args: complete set of field values, in .msg order
00147     :param kwds: use keyword arguments corresponding to message field names
00148     to set specific fields.
00149     """
00150     if args or kwds:
00151       super(TrackMsg, self).__init__(*args, **kwds)
00152       #message fields cannot be None, assign default values for those that are
00153       if self.header is None:
00154         self.header = std_msgs.msg.Header()
00155       if self.id is None:
00156         self.id = 0
00157       if self.pose is None:
00158         self.pose = []
00159       if self.pose_headers is None:
00160         self.pose_headers = []
00161       if self.pose_projected is None:
00162         self.pose_projected = []
00163       if self.pose_resampled is None:
00164         self.pose_resampled = []
00165       if self.pose_flags is None:
00166         self.pose_flags = []
00167       if self.channels is None:
00168         self.channels = []
00169     else:
00170       self.header = std_msgs.msg.Header()
00171       self.id = 0
00172       self.pose = []
00173       self.pose_headers = []
00174       self.pose_projected = []
00175       self.pose_resampled = []
00176       self.pose_flags = []
00177       self.channels = []
00178 
00179   def _get_types(self):
00180     """
00181     internal API method
00182     """
00183     return self._slot_types
00184 
00185   def serialize(self, buff):
00186     """
00187     serialize message into buffer
00188     :param buff: buffer, ``StringIO``
00189     """
00190     try:
00191       _x = self
00192       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00193       _x = self.header.frame_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       buff.write(_struct_i.pack(self.id))
00200       length = len(self.pose)
00201       buff.write(_struct_I.pack(length))
00202       for val1 in self.pose:
00203         _v1 = val1.position
00204         _x = _v1
00205         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00206         _v2 = val1.orientation
00207         _x = _v2
00208         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00209       length = len(self.pose_headers)
00210       buff.write(_struct_I.pack(length))
00211       for val1 in self.pose_headers:
00212         buff.write(_struct_I.pack(val1.seq))
00213         _v3 = val1.stamp
00214         _x = _v3
00215         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00216         _x = val1.frame_id
00217         length = len(_x)
00218         if python3 or type(_x) == unicode:
00219           _x = _x.encode('utf-8')
00220           length = len(_x)
00221         buff.write(struct.pack('<I%ss'%length, length, _x))
00222       length = len(self.pose_projected)
00223       buff.write(_struct_I.pack(length))
00224       for val1 in self.pose_projected:
00225         _v4 = val1.position
00226         _x = _v4
00227         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00228         _v5 = val1.orientation
00229         _x = _v5
00230         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00231       length = len(self.pose_resampled)
00232       buff.write(_struct_I.pack(length))
00233       for val1 in self.pose_resampled:
00234         _v6 = val1.position
00235         _x = _v6
00236         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00237         _v7 = val1.orientation
00238         _x = _v7
00239         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00240       length = len(self.pose_flags)
00241       buff.write(_struct_I.pack(length))
00242       pattern = '<%sI'%length
00243       buff.write(struct.pack(pattern, *self.pose_flags))
00244       length = len(self.channels)
00245       buff.write(_struct_I.pack(length))
00246       for val1 in self.channels:
00247         _x = val1.name
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         length = len(val1.values)
00254         buff.write(_struct_I.pack(length))
00255         pattern = '<%sf'%length
00256         buff.write(struct.pack(pattern, *val1.values))
00257     except struct.error as se: self._check_types(se)
00258     except TypeError as te: self._check_types(te)
00259 
00260   def deserialize(self, str):
00261     """
00262     unpack serialized message in str into this message instance
00263     :param str: byte array of serialized message, ``str``
00264     """
00265     try:
00266       if self.header is None:
00267         self.header = std_msgs.msg.Header()
00268       if self.pose is None:
00269         self.pose = None
00270       if self.pose_headers is None:
00271         self.pose_headers = None
00272       if self.pose_projected is None:
00273         self.pose_projected = None
00274       if self.pose_resampled is None:
00275         self.pose_resampled = None
00276       if self.channels is None:
00277         self.channels = None
00278       end = 0
00279       _x = self
00280       start = end
00281       end += 12
00282       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00283       start = end
00284       end += 4
00285       (length,) = _struct_I.unpack(str[start:end])
00286       start = end
00287       end += length
00288       if python3:
00289         self.header.frame_id = str[start:end].decode('utf-8')
00290       else:
00291         self.header.frame_id = str[start:end]
00292       start = end
00293       end += 4
00294       (self.id,) = _struct_i.unpack(str[start:end])
00295       start = end
00296       end += 4
00297       (length,) = _struct_I.unpack(str[start:end])
00298       self.pose = []
00299       for i in range(0, length):
00300         val1 = geometry_msgs.msg.Pose()
00301         _v8 = val1.position
00302         _x = _v8
00303         start = end
00304         end += 24
00305         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00306         _v9 = val1.orientation
00307         _x = _v9
00308         start = end
00309         end += 32
00310         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00311         self.pose.append(val1)
00312       start = end
00313       end += 4
00314       (length,) = _struct_I.unpack(str[start:end])
00315       self.pose_headers = []
00316       for i in range(0, length):
00317         val1 = std_msgs.msg.Header()
00318         start = end
00319         end += 4
00320         (val1.seq,) = _struct_I.unpack(str[start:end])
00321         _v10 = val1.stamp
00322         _x = _v10
00323         start = end
00324         end += 8
00325         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00326         start = end
00327         end += 4
00328         (length,) = _struct_I.unpack(str[start:end])
00329         start = end
00330         end += length
00331         if python3:
00332           val1.frame_id = str[start:end].decode('utf-8')
00333         else:
00334           val1.frame_id = str[start:end]
00335         self.pose_headers.append(val1)
00336       start = end
00337       end += 4
00338       (length,) = _struct_I.unpack(str[start:end])
00339       self.pose_projected = []
00340       for i in range(0, length):
00341         val1 = geometry_msgs.msg.Pose()
00342         _v11 = val1.position
00343         _x = _v11
00344         start = end
00345         end += 24
00346         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00347         _v12 = val1.orientation
00348         _x = _v12
00349         start = end
00350         end += 32
00351         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00352         self.pose_projected.append(val1)
00353       start = end
00354       end += 4
00355       (length,) = _struct_I.unpack(str[start:end])
00356       self.pose_resampled = []
00357       for i in range(0, length):
00358         val1 = geometry_msgs.msg.Pose()
00359         _v13 = val1.position
00360         _x = _v13
00361         start = end
00362         end += 24
00363         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00364         _v14 = val1.orientation
00365         _x = _v14
00366         start = end
00367         end += 32
00368         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00369         self.pose_resampled.append(val1)
00370       start = end
00371       end += 4
00372       (length,) = _struct_I.unpack(str[start:end])
00373       pattern = '<%sI'%length
00374       start = end
00375       end += struct.calcsize(pattern)
00376       self.pose_flags = struct.unpack(pattern, str[start:end])
00377       start = end
00378       end += 4
00379       (length,) = _struct_I.unpack(str[start:end])
00380       self.channels = []
00381       for i in range(0, length):
00382         val1 = sensor_msgs.msg.ChannelFloat32()
00383         start = end
00384         end += 4
00385         (length,) = _struct_I.unpack(str[start:end])
00386         start = end
00387         end += length
00388         if python3:
00389           val1.name = str[start:end].decode('utf-8')
00390         else:
00391           val1.name = str[start:end]
00392         start = end
00393         end += 4
00394         (length,) = _struct_I.unpack(str[start:end])
00395         pattern = '<%sf'%length
00396         start = end
00397         end += struct.calcsize(pattern)
00398         val1.values = struct.unpack(pattern, str[start:end])
00399         self.channels.append(val1)
00400       return self
00401     except struct.error as e:
00402       raise genpy.DeserializationError(e) #most likely buffer underfill
00403 
00404 
00405   def serialize_numpy(self, buff, numpy):
00406     """
00407     serialize message with numpy array types into buffer
00408     :param buff: buffer, ``StringIO``
00409     :param numpy: numpy python module
00410     """
00411     try:
00412       _x = self
00413       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00414       _x = self.header.frame_id
00415       length = len(_x)
00416       if python3 or type(_x) == unicode:
00417         _x = _x.encode('utf-8')
00418         length = len(_x)
00419       buff.write(struct.pack('<I%ss'%length, length, _x))
00420       buff.write(_struct_i.pack(self.id))
00421       length = len(self.pose)
00422       buff.write(_struct_I.pack(length))
00423       for val1 in self.pose:
00424         _v15 = val1.position
00425         _x = _v15
00426         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00427         _v16 = val1.orientation
00428         _x = _v16
00429         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00430       length = len(self.pose_headers)
00431       buff.write(_struct_I.pack(length))
00432       for val1 in self.pose_headers:
00433         buff.write(_struct_I.pack(val1.seq))
00434         _v17 = val1.stamp
00435         _x = _v17
00436         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00437         _x = val1.frame_id
00438         length = len(_x)
00439         if python3 or type(_x) == unicode:
00440           _x = _x.encode('utf-8')
00441           length = len(_x)
00442         buff.write(struct.pack('<I%ss'%length, length, _x))
00443       length = len(self.pose_projected)
00444       buff.write(_struct_I.pack(length))
00445       for val1 in self.pose_projected:
00446         _v18 = val1.position
00447         _x = _v18
00448         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00449         _v19 = val1.orientation
00450         _x = _v19
00451         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00452       length = len(self.pose_resampled)
00453       buff.write(_struct_I.pack(length))
00454       for val1 in self.pose_resampled:
00455         _v20 = val1.position
00456         _x = _v20
00457         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00458         _v21 = val1.orientation
00459         _x = _v21
00460         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00461       length = len(self.pose_flags)
00462       buff.write(_struct_I.pack(length))
00463       pattern = '<%sI'%length
00464       buff.write(self.pose_flags.tostring())
00465       length = len(self.channels)
00466       buff.write(_struct_I.pack(length))
00467       for val1 in self.channels:
00468         _x = val1.name
00469         length = len(_x)
00470         if python3 or type(_x) == unicode:
00471           _x = _x.encode('utf-8')
00472           length = len(_x)
00473         buff.write(struct.pack('<I%ss'%length, length, _x))
00474         length = len(val1.values)
00475         buff.write(_struct_I.pack(length))
00476         pattern = '<%sf'%length
00477         buff.write(val1.values.tostring())
00478     except struct.error as se: self._check_types(se)
00479     except TypeError as te: self._check_types(te)
00480 
00481   def deserialize_numpy(self, str, numpy):
00482     """
00483     unpack serialized message in str into this message instance using numpy for array types
00484     :param str: byte array of serialized message, ``str``
00485     :param numpy: numpy python module
00486     """
00487     try:
00488       if self.header is None:
00489         self.header = std_msgs.msg.Header()
00490       if self.pose is None:
00491         self.pose = None
00492       if self.pose_headers is None:
00493         self.pose_headers = None
00494       if self.pose_projected is None:
00495         self.pose_projected = None
00496       if self.pose_resampled is None:
00497         self.pose_resampled = None
00498       if self.channels is None:
00499         self.channels = None
00500       end = 0
00501       _x = self
00502       start = end
00503       end += 12
00504       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00505       start = end
00506       end += 4
00507       (length,) = _struct_I.unpack(str[start:end])
00508       start = end
00509       end += length
00510       if python3:
00511         self.header.frame_id = str[start:end].decode('utf-8')
00512       else:
00513         self.header.frame_id = str[start:end]
00514       start = end
00515       end += 4
00516       (self.id,) = _struct_i.unpack(str[start:end])
00517       start = end
00518       end += 4
00519       (length,) = _struct_I.unpack(str[start:end])
00520       self.pose = []
00521       for i in range(0, length):
00522         val1 = geometry_msgs.msg.Pose()
00523         _v22 = val1.position
00524         _x = _v22
00525         start = end
00526         end += 24
00527         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00528         _v23 = val1.orientation
00529         _x = _v23
00530         start = end
00531         end += 32
00532         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00533         self.pose.append(val1)
00534       start = end
00535       end += 4
00536       (length,) = _struct_I.unpack(str[start:end])
00537       self.pose_headers = []
00538       for i in range(0, length):
00539         val1 = std_msgs.msg.Header()
00540         start = end
00541         end += 4
00542         (val1.seq,) = _struct_I.unpack(str[start:end])
00543         _v24 = val1.stamp
00544         _x = _v24
00545         start = end
00546         end += 8
00547         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00548         start = end
00549         end += 4
00550         (length,) = _struct_I.unpack(str[start:end])
00551         start = end
00552         end += length
00553         if python3:
00554           val1.frame_id = str[start:end].decode('utf-8')
00555         else:
00556           val1.frame_id = str[start:end]
00557         self.pose_headers.append(val1)
00558       start = end
00559       end += 4
00560       (length,) = _struct_I.unpack(str[start:end])
00561       self.pose_projected = []
00562       for i in range(0, length):
00563         val1 = geometry_msgs.msg.Pose()
00564         _v25 = val1.position
00565         _x = _v25
00566         start = end
00567         end += 24
00568         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00569         _v26 = val1.orientation
00570         _x = _v26
00571         start = end
00572         end += 32
00573         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00574         self.pose_projected.append(val1)
00575       start = end
00576       end += 4
00577       (length,) = _struct_I.unpack(str[start:end])
00578       self.pose_resampled = []
00579       for i in range(0, length):
00580         val1 = geometry_msgs.msg.Pose()
00581         _v27 = val1.position
00582         _x = _v27
00583         start = end
00584         end += 24
00585         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00586         _v28 = val1.orientation
00587         _x = _v28
00588         start = end
00589         end += 32
00590         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00591         self.pose_resampled.append(val1)
00592       start = end
00593       end += 4
00594       (length,) = _struct_I.unpack(str[start:end])
00595       pattern = '<%sI'%length
00596       start = end
00597       end += struct.calcsize(pattern)
00598       self.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
00599       start = end
00600       end += 4
00601       (length,) = _struct_I.unpack(str[start:end])
00602       self.channels = []
00603       for i in range(0, length):
00604         val1 = sensor_msgs.msg.ChannelFloat32()
00605         start = end
00606         end += 4
00607         (length,) = _struct_I.unpack(str[start:end])
00608         start = end
00609         end += length
00610         if python3:
00611           val1.name = str[start:end].decode('utf-8')
00612         else:
00613           val1.name = str[start:end]
00614         start = end
00615         end += 4
00616         (length,) = _struct_I.unpack(str[start:end])
00617         pattern = '<%sf'%length
00618         start = end
00619         end += struct.calcsize(pattern)
00620         val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00621         self.channels.append(val1)
00622       return self
00623     except struct.error as e:
00624       raise genpy.DeserializationError(e) #most likely buffer underfill
00625 
00626 _struct_I = genpy.struct_I
00627 _struct_i = struct.Struct("<i")
00628 _struct_3I = struct.Struct("<3I")
00629 _struct_4d = struct.Struct("<4d")
00630 _struct_2I = struct.Struct("<2I")
00631 _struct_3d = struct.Struct("<3d")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


articulation_msgs
Author(s): Juergen Sturm
autogenerated on Wed Dec 26 2012 15:30:49