_ImageFeature1D.py
Go to the documentation of this file.
00001 """autogenerated by genpy from posedetection_msgs/ImageFeature1D.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 std_msgs.msg
00008 import posedetection_msgs.msg
00009 import sensor_msgs.msg
00010 
00011 class ImageFeature1D(genpy.Message):
00012   _md5sum = "bfd3a262e6342c55b7e11fccf00d8b2c"
00013   _type = "posedetection_msgs/ImageFeature1D"
00014   _has_header = False #flag to mark the presence of a Header object
00015   _full_text = """# synchronized image and features message
00016 sensor_msgs/Image image
00017 sensor_msgs/CameraInfo info
00018 posedetection_msgs/Feature1D features
00019 
00020 ================================================================================
00021 MSG: sensor_msgs/Image
00022 # This message contains an uncompressed image
00023 # (0, 0) is at top-left corner of image
00024 #
00025 
00026 Header header        # Header timestamp should be acquisition time of image
00027                      # Header frame_id should be optical frame of camera
00028                      # origin of frame should be optical center of cameara
00029                      # +x should point to the right in the image
00030                      # +y should point down in the image
00031                      # +z should point into to plane of the image
00032                      # If the frame_id here and the frame_id of the CameraInfo
00033                      # message associated with the image conflict
00034                      # the behavior is undefined
00035 
00036 uint32 height         # image height, that is, number of rows
00037 uint32 width          # image width, that is, number of columns
00038 
00039 # The legal values for encoding are in file src/image_encodings.cpp
00040 # If you want to standardize a new string format, join
00041 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00042 
00043 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00044                       # taken from the list of strings in src/image_encodings.cpp
00045 
00046 uint8 is_bigendian    # is this data bigendian?
00047 uint32 step           # Full row length in bytes
00048 uint8[] data          # actual matrix data, size is (step * rows)
00049 
00050 ================================================================================
00051 MSG: std_msgs/Header
00052 # Standard metadata for higher-level stamped data types.
00053 # This is generally used to communicate timestamped data 
00054 # in a particular coordinate frame.
00055 # 
00056 # sequence ID: consecutively increasing ID 
00057 uint32 seq
00058 #Two-integer timestamp that is expressed as:
00059 # * stamp.secs: seconds (stamp_secs) since epoch
00060 # * stamp.nsecs: nanoseconds since stamp_secs
00061 # time-handling sugar is provided by the client library
00062 time stamp
00063 #Frame this data is associated with
00064 # 0: no frame
00065 # 1: global frame
00066 string frame_id
00067 
00068 ================================================================================
00069 MSG: sensor_msgs/CameraInfo
00070 # This message defines meta information for a camera. It should be in a
00071 # camera namespace on topic "camera_info" and accompanied by up to five
00072 # image topics named:
00073 #
00074 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00075 #   image            - monochrome, distorted
00076 #   image_color      - color, distorted
00077 #   image_rect       - monochrome, rectified
00078 #   image_rect_color - color, rectified
00079 #
00080 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00081 # for producing the four processed image topics from image_raw and
00082 # camera_info. The meaning of the camera parameters are described in
00083 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00084 #
00085 # The image_geometry package provides a user-friendly interface to
00086 # common operations using this meta information. If you want to, e.g.,
00087 # project a 3d point into image coordinates, we strongly recommend
00088 # using image_geometry.
00089 #
00090 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00091 # zeroed out. In particular, clients may assume that K[0] == 0.0
00092 # indicates an uncalibrated camera.
00093 
00094 #######################################################################
00095 #                     Image acquisition info                          #
00096 #######################################################################
00097 
00098 # Time of image acquisition, camera coordinate frame ID
00099 Header header    # Header timestamp should be acquisition time of image
00100                  # Header frame_id should be optical frame of camera
00101                  # origin of frame should be optical center of camera
00102                  # +x should point to the right in the image
00103                  # +y should point down in the image
00104                  # +z should point into the plane of the image
00105 
00106 
00107 #######################################################################
00108 #                      Calibration Parameters                         #
00109 #######################################################################
00110 # These are fixed during camera calibration. Their values will be the #
00111 # same in all messages until the camera is recalibrated. Note that    #
00112 # self-calibrating systems may "recalibrate" frequently.              #
00113 #                                                                     #
00114 # The internal parameters can be used to warp a raw (distorted) image #
00115 # to:                                                                 #
00116 #   1. An undistorted image (requires D and K)                        #
00117 #   2. A rectified image (requires D, K, R)                           #
00118 # The projection matrix P projects 3D points into the rectified image.#
00119 #######################################################################
00120 
00121 # The image dimensions with which the camera was calibrated. Normally
00122 # this will be the full camera resolution in pixels.
00123 uint32 height
00124 uint32 width
00125 
00126 # The distortion model used. Supported models are listed in
00127 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00128 # simple model of radial and tangential distortion - is sufficent.
00129 string distortion_model
00130 
00131 # The distortion parameters, size depending on the distortion model.
00132 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00133 float64[] D
00134 
00135 # Intrinsic camera matrix for the raw (distorted) images.
00136 #     [fx  0 cx]
00137 # K = [ 0 fy cy]
00138 #     [ 0  0  1]
00139 # Projects 3D points in the camera coordinate frame to 2D pixel
00140 # coordinates using the focal lengths (fx, fy) and principal point
00141 # (cx, cy).
00142 float64[9]  K # 3x3 row-major matrix
00143 
00144 # Rectification matrix (stereo cameras only)
00145 # A rotation matrix aligning the camera coordinate system to the ideal
00146 # stereo image plane so that epipolar lines in both stereo images are
00147 # parallel.
00148 float64[9]  R # 3x3 row-major matrix
00149 
00150 # Projection/camera matrix
00151 #     [fx'  0  cx' Tx]
00152 # P = [ 0  fy' cy' Ty]
00153 #     [ 0   0   1   0]
00154 # By convention, this matrix specifies the intrinsic (camera) matrix
00155 #  of the processed (rectified) image. That is, the left 3x3 portion
00156 #  is the normal camera intrinsic matrix for the rectified image.
00157 # It projects 3D points in the camera coordinate frame to 2D pixel
00158 #  coordinates using the focal lengths (fx', fy') and principal point
00159 #  (cx', cy') - these may differ from the values in K.
00160 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00161 #  also have R = the identity and P[1:3,1:3] = K.
00162 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00163 #  position of the optical center of the second camera in the first
00164 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00165 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00166 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00167 #  Tx = -fx' * B, where B is the baseline between the cameras.
00168 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00169 #  the rectified image is given by:
00170 #  [u v w]' = P * [X Y Z 1]'
00171 #         x = u / w
00172 #         y = v / w
00173 #  This holds for both images of a stereo pair.
00174 float64[12] P # 3x4 row-major matrix
00175 
00176 
00177 #######################################################################
00178 #                      Operational Parameters                         #
00179 #######################################################################
00180 # These define the image region actually captured by the camera       #
00181 # driver. Although they affect the geometry of the output image, they #
00182 # may be changed freely without recalibrating the camera.             #
00183 #######################################################################
00184 
00185 # Binning refers here to any camera setting which combines rectangular
00186 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00187 #  resolution of the output image to
00188 #  (width / binning_x) x (height / binning_y).
00189 # The default values binning_x = binning_y = 0 is considered the same
00190 #  as binning_x = binning_y = 1 (no subsampling).
00191 uint32 binning_x
00192 uint32 binning_y
00193 
00194 # Region of interest (subwindow of full camera resolution), given in
00195 #  full resolution (unbinned) image coordinates. A particular ROI
00196 #  always denotes the same window of pixels on the camera sensor,
00197 #  regardless of binning settings.
00198 # The default setting of roi (all values 0) is considered the same as
00199 #  full resolution (roi.width = width, roi.height = height).
00200 RegionOfInterest roi
00201 
00202 ================================================================================
00203 MSG: sensor_msgs/RegionOfInterest
00204 # This message is used to specify a region of interest within an image.
00205 #
00206 # When used to specify the ROI setting of the camera when the image was
00207 # taken, the height and width fields should either match the height and
00208 # width fields for the associated image; or height = width = 0
00209 # indicates that the full resolution image was captured.
00210 
00211 uint32 x_offset  # Leftmost pixel of the ROI
00212                  # (0 if the ROI includes the left edge of the image)
00213 uint32 y_offset  # Topmost pixel of the ROI
00214                  # (0 if the ROI includes the top edge of the image)
00215 uint32 height    # Height of ROI
00216 uint32 width     # Width of ROI
00217 
00218 # True if a distinct rectified ROI should be calculated from the "raw"
00219 # ROI in this message. Typically this should be False if the full image
00220 # is captured (ROI not used), and True if a subwindow is captured (ROI
00221 # used).
00222 bool do_rectify
00223 
00224 ================================================================================
00225 MSG: posedetection_msgs/Feature1D
00226 Header header
00227 Curve1D[] lines # N, 0-indexed
00228 float32[] descriptors # N*descriptor_dim
00229 float32[] confidences # optional
00230 int32 descriptor_dim
00231 
00232 ================================================================================
00233 MSG: posedetection_msgs/Curve1D
00234 float32[] pts # 2xN points in the image
00235 
00236 """
00237   __slots__ = ['image','info','features']
00238   _slot_types = ['sensor_msgs/Image','sensor_msgs/CameraInfo','posedetection_msgs/Feature1D']
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        image,info,features
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(ImageFeature1D, self).__init__(*args, **kwds)
00256       #message fields cannot be None, assign default values for those that are
00257       if self.image is None:
00258         self.image = sensor_msgs.msg.Image()
00259       if self.info is None:
00260         self.info = sensor_msgs.msg.CameraInfo()
00261       if self.features is None:
00262         self.features = posedetection_msgs.msg.Feature1D()
00263     else:
00264       self.image = sensor_msgs.msg.Image()
00265       self.info = sensor_msgs.msg.CameraInfo()
00266       self.features = posedetection_msgs.msg.Feature1D()
00267 
00268   def _get_types(self):
00269     """
00270     internal API method
00271     """
00272     return self._slot_types
00273 
00274   def serialize(self, buff):
00275     """
00276     serialize message into buffer
00277     :param buff: buffer, ``StringIO``
00278     """
00279     try:
00280       _x = self
00281       buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00282       _x = self.image.header.frame_id
00283       length = len(_x)
00284       if python3 or type(_x) == unicode:
00285         _x = _x.encode('utf-8')
00286         length = len(_x)
00287       buff.write(struct.pack('<I%ss'%length, length, _x))
00288       _x = self
00289       buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00290       _x = self.image.encoding
00291       length = len(_x)
00292       if python3 or type(_x) == unicode:
00293         _x = _x.encode('utf-8')
00294         length = len(_x)
00295       buff.write(struct.pack('<I%ss'%length, length, _x))
00296       _x = self
00297       buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00298       _x = self.image.data
00299       length = len(_x)
00300       # - if encoded as a list instead, serialize as bytes instead of string
00301       if type(_x) in [list, tuple]:
00302         buff.write(struct.pack('<I%sB'%length, length, *_x))
00303       else:
00304         buff.write(struct.pack('<I%ss'%length, length, _x))
00305       _x = self
00306       buff.write(_struct_3I.pack(_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs))
00307       _x = self.info.header.frame_id
00308       length = len(_x)
00309       if python3 or type(_x) == unicode:
00310         _x = _x.encode('utf-8')
00311         length = len(_x)
00312       buff.write(struct.pack('<I%ss'%length, length, _x))
00313       _x = self
00314       buff.write(_struct_2I.pack(_x.info.height, _x.info.width))
00315       _x = self.info.distortion_model
00316       length = len(_x)
00317       if python3 or type(_x) == unicode:
00318         _x = _x.encode('utf-8')
00319         length = len(_x)
00320       buff.write(struct.pack('<I%ss'%length, length, _x))
00321       length = len(self.info.D)
00322       buff.write(_struct_I.pack(length))
00323       pattern = '<%sd'%length
00324       buff.write(struct.pack(pattern, *self.info.D))
00325       buff.write(_struct_9d.pack(*self.info.K))
00326       buff.write(_struct_9d.pack(*self.info.R))
00327       buff.write(_struct_12d.pack(*self.info.P))
00328       _x = self
00329       buff.write(_struct_6IB3I.pack(_x.info.binning_x, _x.info.binning_y, _x.info.roi.x_offset, _x.info.roi.y_offset, _x.info.roi.height, _x.info.roi.width, _x.info.roi.do_rectify, _x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs))
00330       _x = self.features.header.frame_id
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       length = len(self.features.lines)
00337       buff.write(_struct_I.pack(length))
00338       for val1 in self.features.lines:
00339         length = len(val1.pts)
00340         buff.write(_struct_I.pack(length))
00341         pattern = '<%sf'%length
00342         buff.write(struct.pack(pattern, *val1.pts))
00343       length = len(self.features.descriptors)
00344       buff.write(_struct_I.pack(length))
00345       pattern = '<%sf'%length
00346       buff.write(struct.pack(pattern, *self.features.descriptors))
00347       length = len(self.features.confidences)
00348       buff.write(_struct_I.pack(length))
00349       pattern = '<%sf'%length
00350       buff.write(struct.pack(pattern, *self.features.confidences))
00351       buff.write(_struct_i.pack(self.features.descriptor_dim))
00352     except struct.error as se: self._check_types(se)
00353     except TypeError as te: self._check_types(te)
00354 
00355   def deserialize(self, str):
00356     """
00357     unpack serialized message in str into this message instance
00358     :param str: byte array of serialized message, ``str``
00359     """
00360     try:
00361       if self.image is None:
00362         self.image = sensor_msgs.msg.Image()
00363       if self.info is None:
00364         self.info = sensor_msgs.msg.CameraInfo()
00365       if self.features is None:
00366         self.features = posedetection_msgs.msg.Feature1D()
00367       end = 0
00368       _x = self
00369       start = end
00370       end += 12
00371       (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00372       start = end
00373       end += 4
00374       (length,) = _struct_I.unpack(str[start:end])
00375       start = end
00376       end += length
00377       if python3:
00378         self.image.header.frame_id = str[start:end].decode('utf-8')
00379       else:
00380         self.image.header.frame_id = str[start:end]
00381       _x = self
00382       start = end
00383       end += 8
00384       (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00385       start = end
00386       end += 4
00387       (length,) = _struct_I.unpack(str[start:end])
00388       start = end
00389       end += length
00390       if python3:
00391         self.image.encoding = str[start:end].decode('utf-8')
00392       else:
00393         self.image.encoding = str[start:end]
00394       _x = self
00395       start = end
00396       end += 5
00397       (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00398       start = end
00399       end += 4
00400       (length,) = _struct_I.unpack(str[start:end])
00401       start = end
00402       end += length
00403       if python3:
00404         self.image.data = str[start:end].decode('utf-8')
00405       else:
00406         self.image.data = str[start:end]
00407       _x = self
00408       start = end
00409       end += 12
00410       (_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00411       start = end
00412       end += 4
00413       (length,) = _struct_I.unpack(str[start:end])
00414       start = end
00415       end += length
00416       if python3:
00417         self.info.header.frame_id = str[start:end].decode('utf-8')
00418       else:
00419         self.info.header.frame_id = str[start:end]
00420       _x = self
00421       start = end
00422       end += 8
00423       (_x.info.height, _x.info.width,) = _struct_2I.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.info.distortion_model = str[start:end].decode('utf-8')
00431       else:
00432         self.info.distortion_model = str[start:end]
00433       start = end
00434       end += 4
00435       (length,) = _struct_I.unpack(str[start:end])
00436       pattern = '<%sd'%length
00437       start = end
00438       end += struct.calcsize(pattern)
00439       self.info.D = struct.unpack(pattern, str[start:end])
00440       start = end
00441       end += 72
00442       self.info.K = _struct_9d.unpack(str[start:end])
00443       start = end
00444       end += 72
00445       self.info.R = _struct_9d.unpack(str[start:end])
00446       start = end
00447       end += 96
00448       self.info.P = _struct_12d.unpack(str[start:end])
00449       _x = self
00450       start = end
00451       end += 37
00452       (_x.info.binning_x, _x.info.binning_y, _x.info.roi.x_offset, _x.info.roi.y_offset, _x.info.roi.height, _x.info.roi.width, _x.info.roi.do_rectify, _x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00453       self.info.roi.do_rectify = bool(self.info.roi.do_rectify)
00454       start = end
00455       end += 4
00456       (length,) = _struct_I.unpack(str[start:end])
00457       start = end
00458       end += length
00459       if python3:
00460         self.features.header.frame_id = str[start:end].decode('utf-8')
00461       else:
00462         self.features.header.frame_id = str[start:end]
00463       start = end
00464       end += 4
00465       (length,) = _struct_I.unpack(str[start:end])
00466       self.features.lines = []
00467       for i in range(0, length):
00468         val1 = posedetection_msgs.msg.Curve1D()
00469         start = end
00470         end += 4
00471         (length,) = _struct_I.unpack(str[start:end])
00472         pattern = '<%sf'%length
00473         start = end
00474         end += struct.calcsize(pattern)
00475         val1.pts = struct.unpack(pattern, str[start:end])
00476         self.features.lines.append(val1)
00477       start = end
00478       end += 4
00479       (length,) = _struct_I.unpack(str[start:end])
00480       pattern = '<%sf'%length
00481       start = end
00482       end += struct.calcsize(pattern)
00483       self.features.descriptors = struct.unpack(pattern, str[start:end])
00484       start = end
00485       end += 4
00486       (length,) = _struct_I.unpack(str[start:end])
00487       pattern = '<%sf'%length
00488       start = end
00489       end += struct.calcsize(pattern)
00490       self.features.confidences = struct.unpack(pattern, str[start:end])
00491       start = end
00492       end += 4
00493       (self.features.descriptor_dim,) = _struct_i.unpack(str[start:end])
00494       return self
00495     except struct.error as e:
00496       raise genpy.DeserializationError(e) #most likely buffer underfill
00497 
00498 
00499   def serialize_numpy(self, buff, numpy):
00500     """
00501     serialize message with numpy array types into buffer
00502     :param buff: buffer, ``StringIO``
00503     :param numpy: numpy python module
00504     """
00505     try:
00506       _x = self
00507       buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00508       _x = self.image.header.frame_id
00509       length = len(_x)
00510       if python3 or type(_x) == unicode:
00511         _x = _x.encode('utf-8')
00512         length = len(_x)
00513       buff.write(struct.pack('<I%ss'%length, length, _x))
00514       _x = self
00515       buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00516       _x = self.image.encoding
00517       length = len(_x)
00518       if python3 or type(_x) == unicode:
00519         _x = _x.encode('utf-8')
00520         length = len(_x)
00521       buff.write(struct.pack('<I%ss'%length, length, _x))
00522       _x = self
00523       buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00524       _x = self.image.data
00525       length = len(_x)
00526       # - if encoded as a list instead, serialize as bytes instead of string
00527       if type(_x) in [list, tuple]:
00528         buff.write(struct.pack('<I%sB'%length, length, *_x))
00529       else:
00530         buff.write(struct.pack('<I%ss'%length, length, _x))
00531       _x = self
00532       buff.write(_struct_3I.pack(_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs))
00533       _x = self.info.header.frame_id
00534       length = len(_x)
00535       if python3 or type(_x) == unicode:
00536         _x = _x.encode('utf-8')
00537         length = len(_x)
00538       buff.write(struct.pack('<I%ss'%length, length, _x))
00539       _x = self
00540       buff.write(_struct_2I.pack(_x.info.height, _x.info.width))
00541       _x = self.info.distortion_model
00542       length = len(_x)
00543       if python3 or type(_x) == unicode:
00544         _x = _x.encode('utf-8')
00545         length = len(_x)
00546       buff.write(struct.pack('<I%ss'%length, length, _x))
00547       length = len(self.info.D)
00548       buff.write(_struct_I.pack(length))
00549       pattern = '<%sd'%length
00550       buff.write(self.info.D.tostring())
00551       buff.write(self.info.K.tostring())
00552       buff.write(self.info.R.tostring())
00553       buff.write(self.info.P.tostring())
00554       _x = self
00555       buff.write(_struct_6IB3I.pack(_x.info.binning_x, _x.info.binning_y, _x.info.roi.x_offset, _x.info.roi.y_offset, _x.info.roi.height, _x.info.roi.width, _x.info.roi.do_rectify, _x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs))
00556       _x = self.features.header.frame_id
00557       length = len(_x)
00558       if python3 or type(_x) == unicode:
00559         _x = _x.encode('utf-8')
00560         length = len(_x)
00561       buff.write(struct.pack('<I%ss'%length, length, _x))
00562       length = len(self.features.lines)
00563       buff.write(_struct_I.pack(length))
00564       for val1 in self.features.lines:
00565         length = len(val1.pts)
00566         buff.write(_struct_I.pack(length))
00567         pattern = '<%sf'%length
00568         buff.write(val1.pts.tostring())
00569       length = len(self.features.descriptors)
00570       buff.write(_struct_I.pack(length))
00571       pattern = '<%sf'%length
00572       buff.write(self.features.descriptors.tostring())
00573       length = len(self.features.confidences)
00574       buff.write(_struct_I.pack(length))
00575       pattern = '<%sf'%length
00576       buff.write(self.features.confidences.tostring())
00577       buff.write(_struct_i.pack(self.features.descriptor_dim))
00578     except struct.error as se: self._check_types(se)
00579     except TypeError as te: self._check_types(te)
00580 
00581   def deserialize_numpy(self, str, numpy):
00582     """
00583     unpack serialized message in str into this message instance using numpy for array types
00584     :param str: byte array of serialized message, ``str``
00585     :param numpy: numpy python module
00586     """
00587     try:
00588       if self.image is None:
00589         self.image = sensor_msgs.msg.Image()
00590       if self.info is None:
00591         self.info = sensor_msgs.msg.CameraInfo()
00592       if self.features is None:
00593         self.features = posedetection_msgs.msg.Feature1D()
00594       end = 0
00595       _x = self
00596       start = end
00597       end += 12
00598       (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00599       start = end
00600       end += 4
00601       (length,) = _struct_I.unpack(str[start:end])
00602       start = end
00603       end += length
00604       if python3:
00605         self.image.header.frame_id = str[start:end].decode('utf-8')
00606       else:
00607         self.image.header.frame_id = str[start:end]
00608       _x = self
00609       start = end
00610       end += 8
00611       (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00612       start = end
00613       end += 4
00614       (length,) = _struct_I.unpack(str[start:end])
00615       start = end
00616       end += length
00617       if python3:
00618         self.image.encoding = str[start:end].decode('utf-8')
00619       else:
00620         self.image.encoding = str[start:end]
00621       _x = self
00622       start = end
00623       end += 5
00624       (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00625       start = end
00626       end += 4
00627       (length,) = _struct_I.unpack(str[start:end])
00628       start = end
00629       end += length
00630       if python3:
00631         self.image.data = str[start:end].decode('utf-8')
00632       else:
00633         self.image.data = str[start:end]
00634       _x = self
00635       start = end
00636       end += 12
00637       (_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00638       start = end
00639       end += 4
00640       (length,) = _struct_I.unpack(str[start:end])
00641       start = end
00642       end += length
00643       if python3:
00644         self.info.header.frame_id = str[start:end].decode('utf-8')
00645       else:
00646         self.info.header.frame_id = str[start:end]
00647       _x = self
00648       start = end
00649       end += 8
00650       (_x.info.height, _x.info.width,) = _struct_2I.unpack(str[start:end])
00651       start = end
00652       end += 4
00653       (length,) = _struct_I.unpack(str[start:end])
00654       start = end
00655       end += length
00656       if python3:
00657         self.info.distortion_model = str[start:end].decode('utf-8')
00658       else:
00659         self.info.distortion_model = str[start:end]
00660       start = end
00661       end += 4
00662       (length,) = _struct_I.unpack(str[start:end])
00663       pattern = '<%sd'%length
00664       start = end
00665       end += struct.calcsize(pattern)
00666       self.info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00667       start = end
00668       end += 72
00669       self.info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00670       start = end
00671       end += 72
00672       self.info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00673       start = end
00674       end += 96
00675       self.info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
00676       _x = self
00677       start = end
00678       end += 37
00679       (_x.info.binning_x, _x.info.binning_y, _x.info.roi.x_offset, _x.info.roi.y_offset, _x.info.roi.height, _x.info.roi.width, _x.info.roi.do_rectify, _x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00680       self.info.roi.do_rectify = bool(self.info.roi.do_rectify)
00681       start = end
00682       end += 4
00683       (length,) = _struct_I.unpack(str[start:end])
00684       start = end
00685       end += length
00686       if python3:
00687         self.features.header.frame_id = str[start:end].decode('utf-8')
00688       else:
00689         self.features.header.frame_id = str[start:end]
00690       start = end
00691       end += 4
00692       (length,) = _struct_I.unpack(str[start:end])
00693       self.features.lines = []
00694       for i in range(0, length):
00695         val1 = posedetection_msgs.msg.Curve1D()
00696         start = end
00697         end += 4
00698         (length,) = _struct_I.unpack(str[start:end])
00699         pattern = '<%sf'%length
00700         start = end
00701         end += struct.calcsize(pattern)
00702         val1.pts = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00703         self.features.lines.append(val1)
00704       start = end
00705       end += 4
00706       (length,) = _struct_I.unpack(str[start:end])
00707       pattern = '<%sf'%length
00708       start = end
00709       end += struct.calcsize(pattern)
00710       self.features.descriptors = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00711       start = end
00712       end += 4
00713       (length,) = _struct_I.unpack(str[start:end])
00714       pattern = '<%sf'%length
00715       start = end
00716       end += struct.calcsize(pattern)
00717       self.features.confidences = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00718       start = end
00719       end += 4
00720       (self.features.descriptor_dim,) = _struct_i.unpack(str[start:end])
00721       return self
00722     except struct.error as e:
00723       raise genpy.DeserializationError(e) #most likely buffer underfill
00724 
00725 _struct_I = genpy.struct_I
00726 _struct_6IB3I = struct.Struct("<6IB3I")
00727 _struct_12d = struct.Struct("<12d")
00728 _struct_i = struct.Struct("<i")
00729 _struct_9d = struct.Struct("<9d")
00730 _struct_BI = struct.Struct("<BI")
00731 _struct_3I = struct.Struct("<3I")
00732 _struct_2I = struct.Struct("<2I")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


posedetection_msgs
Author(s): Rosen Diankov
autogenerated on Sat Mar 23 2013 12:47:59