00001 """autogenerated by genpy from posedetection_msgs/ImageFeature0D.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 ImageFeature0D(genpy.Message):
00012 _md5sum = "a16c5327c89b15820420449cf843ed75"
00013 _type = "posedetection_msgs/ImageFeature0D"
00014 _has_header = False
00015 _full_text = """# synchronized image and features message
00016 sensor_msgs/Image image
00017 sensor_msgs/CameraInfo info
00018 posedetection_msgs/Feature0D 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/Feature0D
00226 Header header
00227 float32[] positions # 2*N, 0-indexed
00228 float32[] scales # N, optional
00229 float32[] orientations # N, optional, along +X is 0
00230 float32[] confidences
00231 float32[] descriptors # N*descriptor_dim
00232 int32 descriptor_dim
00233 string type # type of feature
00234
00235 """
00236 __slots__ = ['image','info','features']
00237 _slot_types = ['sensor_msgs/Image','sensor_msgs/CameraInfo','posedetection_msgs/Feature0D']
00238
00239 def __init__(self, *args, **kwds):
00240 """
00241 Constructor. Any message fields that are implicitly/explicitly
00242 set to None will be assigned a default value. The recommend
00243 use is keyword arguments as this is more robust to future message
00244 changes. You cannot mix in-order arguments and keyword arguments.
00245
00246 The available fields are:
00247 image,info,features
00248
00249 :param args: complete set of field values, in .msg order
00250 :param kwds: use keyword arguments corresponding to message field names
00251 to set specific fields.
00252 """
00253 if args or kwds:
00254 super(ImageFeature0D, self).__init__(*args, **kwds)
00255
00256 if self.image is None:
00257 self.image = sensor_msgs.msg.Image()
00258 if self.info is None:
00259 self.info = sensor_msgs.msg.CameraInfo()
00260 if self.features is None:
00261 self.features = posedetection_msgs.msg.Feature0D()
00262 else:
00263 self.image = sensor_msgs.msg.Image()
00264 self.info = sensor_msgs.msg.CameraInfo()
00265 self.features = posedetection_msgs.msg.Feature0D()
00266
00267 def _get_types(self):
00268 """
00269 internal API method
00270 """
00271 return self._slot_types
00272
00273 def serialize(self, buff):
00274 """
00275 serialize message into buffer
00276 :param buff: buffer, ``StringIO``
00277 """
00278 try:
00279 _x = self
00280 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00281 _x = self.image.header.frame_id
00282 length = len(_x)
00283 if python3 or type(_x) == unicode:
00284 _x = _x.encode('utf-8')
00285 length = len(_x)
00286 buff.write(struct.pack('<I%ss'%length, length, _x))
00287 _x = self
00288 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00289 _x = self.image.encoding
00290 length = len(_x)
00291 if python3 or type(_x) == unicode:
00292 _x = _x.encode('utf-8')
00293 length = len(_x)
00294 buff.write(struct.pack('<I%ss'%length, length, _x))
00295 _x = self
00296 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00297 _x = self.image.data
00298 length = len(_x)
00299
00300 if type(_x) in [list, tuple]:
00301 buff.write(struct.pack('<I%sB'%length, length, *_x))
00302 else:
00303 buff.write(struct.pack('<I%ss'%length, length, _x))
00304 _x = self
00305 buff.write(_struct_3I.pack(_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs))
00306 _x = self.info.header.frame_id
00307 length = len(_x)
00308 if python3 or type(_x) == unicode:
00309 _x = _x.encode('utf-8')
00310 length = len(_x)
00311 buff.write(struct.pack('<I%ss'%length, length, _x))
00312 _x = self
00313 buff.write(_struct_2I.pack(_x.info.height, _x.info.width))
00314 _x = self.info.distortion_model
00315 length = len(_x)
00316 if python3 or type(_x) == unicode:
00317 _x = _x.encode('utf-8')
00318 length = len(_x)
00319 buff.write(struct.pack('<I%ss'%length, length, _x))
00320 length = len(self.info.D)
00321 buff.write(_struct_I.pack(length))
00322 pattern = '<%sd'%length
00323 buff.write(struct.pack(pattern, *self.info.D))
00324 buff.write(_struct_9d.pack(*self.info.K))
00325 buff.write(_struct_9d.pack(*self.info.R))
00326 buff.write(_struct_12d.pack(*self.info.P))
00327 _x = self
00328 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))
00329 _x = self.features.header.frame_id
00330 length = len(_x)
00331 if python3 or type(_x) == unicode:
00332 _x = _x.encode('utf-8')
00333 length = len(_x)
00334 buff.write(struct.pack('<I%ss'%length, length, _x))
00335 length = len(self.features.positions)
00336 buff.write(_struct_I.pack(length))
00337 pattern = '<%sf'%length
00338 buff.write(struct.pack(pattern, *self.features.positions))
00339 length = len(self.features.scales)
00340 buff.write(_struct_I.pack(length))
00341 pattern = '<%sf'%length
00342 buff.write(struct.pack(pattern, *self.features.scales))
00343 length = len(self.features.orientations)
00344 buff.write(_struct_I.pack(length))
00345 pattern = '<%sf'%length
00346 buff.write(struct.pack(pattern, *self.features.orientations))
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 length = len(self.features.descriptors)
00352 buff.write(_struct_I.pack(length))
00353 pattern = '<%sf'%length
00354 buff.write(struct.pack(pattern, *self.features.descriptors))
00355 buff.write(_struct_i.pack(self.features.descriptor_dim))
00356 _x = self.features.type
00357 length = len(_x)
00358 if python3 or type(_x) == unicode:
00359 _x = _x.encode('utf-8')
00360 length = len(_x)
00361 buff.write(struct.pack('<I%ss'%length, length, _x))
00362 except struct.error as se: self._check_types(se)
00363 except TypeError as te: self._check_types(te)
00364
00365 def deserialize(self, str):
00366 """
00367 unpack serialized message in str into this message instance
00368 :param str: byte array of serialized message, ``str``
00369 """
00370 try:
00371 if self.image is None:
00372 self.image = sensor_msgs.msg.Image()
00373 if self.info is None:
00374 self.info = sensor_msgs.msg.CameraInfo()
00375 if self.features is None:
00376 self.features = posedetection_msgs.msg.Feature0D()
00377 end = 0
00378 _x = self
00379 start = end
00380 end += 12
00381 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00382 start = end
00383 end += 4
00384 (length,) = _struct_I.unpack(str[start:end])
00385 start = end
00386 end += length
00387 if python3:
00388 self.image.header.frame_id = str[start:end].decode('utf-8')
00389 else:
00390 self.image.header.frame_id = str[start:end]
00391 _x = self
00392 start = end
00393 end += 8
00394 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00395 start = end
00396 end += 4
00397 (length,) = _struct_I.unpack(str[start:end])
00398 start = end
00399 end += length
00400 if python3:
00401 self.image.encoding = str[start:end].decode('utf-8')
00402 else:
00403 self.image.encoding = str[start:end]
00404 _x = self
00405 start = end
00406 end += 5
00407 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00408 start = end
00409 end += 4
00410 (length,) = _struct_I.unpack(str[start:end])
00411 start = end
00412 end += length
00413 if python3:
00414 self.image.data = str[start:end].decode('utf-8')
00415 else:
00416 self.image.data = str[start:end]
00417 _x = self
00418 start = end
00419 end += 12
00420 (_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00421 start = end
00422 end += 4
00423 (length,) = _struct_I.unpack(str[start:end])
00424 start = end
00425 end += length
00426 if python3:
00427 self.info.header.frame_id = str[start:end].decode('utf-8')
00428 else:
00429 self.info.header.frame_id = str[start:end]
00430 _x = self
00431 start = end
00432 end += 8
00433 (_x.info.height, _x.info.width,) = _struct_2I.unpack(str[start:end])
00434 start = end
00435 end += 4
00436 (length,) = _struct_I.unpack(str[start:end])
00437 start = end
00438 end += length
00439 if python3:
00440 self.info.distortion_model = str[start:end].decode('utf-8')
00441 else:
00442 self.info.distortion_model = str[start:end]
00443 start = end
00444 end += 4
00445 (length,) = _struct_I.unpack(str[start:end])
00446 pattern = '<%sd'%length
00447 start = end
00448 end += struct.calcsize(pattern)
00449 self.info.D = struct.unpack(pattern, str[start:end])
00450 start = end
00451 end += 72
00452 self.info.K = _struct_9d.unpack(str[start:end])
00453 start = end
00454 end += 72
00455 self.info.R = _struct_9d.unpack(str[start:end])
00456 start = end
00457 end += 96
00458 self.info.P = _struct_12d.unpack(str[start:end])
00459 _x = self
00460 start = end
00461 end += 37
00462 (_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])
00463 self.info.roi.do_rectify = bool(self.info.roi.do_rectify)
00464 start = end
00465 end += 4
00466 (length,) = _struct_I.unpack(str[start:end])
00467 start = end
00468 end += length
00469 if python3:
00470 self.features.header.frame_id = str[start:end].decode('utf-8')
00471 else:
00472 self.features.header.frame_id = str[start:end]
00473 start = end
00474 end += 4
00475 (length,) = _struct_I.unpack(str[start:end])
00476 pattern = '<%sf'%length
00477 start = end
00478 end += struct.calcsize(pattern)
00479 self.features.positions = struct.unpack(pattern, str[start:end])
00480 start = end
00481 end += 4
00482 (length,) = _struct_I.unpack(str[start:end])
00483 pattern = '<%sf'%length
00484 start = end
00485 end += struct.calcsize(pattern)
00486 self.features.scales = struct.unpack(pattern, str[start:end])
00487 start = end
00488 end += 4
00489 (length,) = _struct_I.unpack(str[start:end])
00490 pattern = '<%sf'%length
00491 start = end
00492 end += struct.calcsize(pattern)
00493 self.features.orientations = struct.unpack(pattern, str[start:end])
00494 start = end
00495 end += 4
00496 (length,) = _struct_I.unpack(str[start:end])
00497 pattern = '<%sf'%length
00498 start = end
00499 end += struct.calcsize(pattern)
00500 self.features.confidences = struct.unpack(pattern, str[start:end])
00501 start = end
00502 end += 4
00503 (length,) = _struct_I.unpack(str[start:end])
00504 pattern = '<%sf'%length
00505 start = end
00506 end += struct.calcsize(pattern)
00507 self.features.descriptors = struct.unpack(pattern, str[start:end])
00508 start = end
00509 end += 4
00510 (self.features.descriptor_dim,) = _struct_i.unpack(str[start:end])
00511 start = end
00512 end += 4
00513 (length,) = _struct_I.unpack(str[start:end])
00514 start = end
00515 end += length
00516 if python3:
00517 self.features.type = str[start:end].decode('utf-8')
00518 else:
00519 self.features.type = str[start:end]
00520 return self
00521 except struct.error as e:
00522 raise genpy.DeserializationError(e)
00523
00524
00525 def serialize_numpy(self, buff, numpy):
00526 """
00527 serialize message with numpy array types into buffer
00528 :param buff: buffer, ``StringIO``
00529 :param numpy: numpy python module
00530 """
00531 try:
00532 _x = self
00533 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00534 _x = self.image.header.frame_id
00535 length = len(_x)
00536 if python3 or type(_x) == unicode:
00537 _x = _x.encode('utf-8')
00538 length = len(_x)
00539 buff.write(struct.pack('<I%ss'%length, length, _x))
00540 _x = self
00541 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00542 _x = self.image.encoding
00543 length = len(_x)
00544 if python3 or type(_x) == unicode:
00545 _x = _x.encode('utf-8')
00546 length = len(_x)
00547 buff.write(struct.pack('<I%ss'%length, length, _x))
00548 _x = self
00549 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00550 _x = self.image.data
00551 length = len(_x)
00552
00553 if type(_x) in [list, tuple]:
00554 buff.write(struct.pack('<I%sB'%length, length, *_x))
00555 else:
00556 buff.write(struct.pack('<I%ss'%length, length, _x))
00557 _x = self
00558 buff.write(_struct_3I.pack(_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs))
00559 _x = self.info.header.frame_id
00560 length = len(_x)
00561 if python3 or type(_x) == unicode:
00562 _x = _x.encode('utf-8')
00563 length = len(_x)
00564 buff.write(struct.pack('<I%ss'%length, length, _x))
00565 _x = self
00566 buff.write(_struct_2I.pack(_x.info.height, _x.info.width))
00567 _x = self.info.distortion_model
00568 length = len(_x)
00569 if python3 or type(_x) == unicode:
00570 _x = _x.encode('utf-8')
00571 length = len(_x)
00572 buff.write(struct.pack('<I%ss'%length, length, _x))
00573 length = len(self.info.D)
00574 buff.write(_struct_I.pack(length))
00575 pattern = '<%sd'%length
00576 buff.write(self.info.D.tostring())
00577 buff.write(self.info.K.tostring())
00578 buff.write(self.info.R.tostring())
00579 buff.write(self.info.P.tostring())
00580 _x = self
00581 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))
00582 _x = self.features.header.frame_id
00583 length = len(_x)
00584 if python3 or type(_x) == unicode:
00585 _x = _x.encode('utf-8')
00586 length = len(_x)
00587 buff.write(struct.pack('<I%ss'%length, length, _x))
00588 length = len(self.features.positions)
00589 buff.write(_struct_I.pack(length))
00590 pattern = '<%sf'%length
00591 buff.write(self.features.positions.tostring())
00592 length = len(self.features.scales)
00593 buff.write(_struct_I.pack(length))
00594 pattern = '<%sf'%length
00595 buff.write(self.features.scales.tostring())
00596 length = len(self.features.orientations)
00597 buff.write(_struct_I.pack(length))
00598 pattern = '<%sf'%length
00599 buff.write(self.features.orientations.tostring())
00600 length = len(self.features.confidences)
00601 buff.write(_struct_I.pack(length))
00602 pattern = '<%sf'%length
00603 buff.write(self.features.confidences.tostring())
00604 length = len(self.features.descriptors)
00605 buff.write(_struct_I.pack(length))
00606 pattern = '<%sf'%length
00607 buff.write(self.features.descriptors.tostring())
00608 buff.write(_struct_i.pack(self.features.descriptor_dim))
00609 _x = self.features.type
00610 length = len(_x)
00611 if python3 or type(_x) == unicode:
00612 _x = _x.encode('utf-8')
00613 length = len(_x)
00614 buff.write(struct.pack('<I%ss'%length, length, _x))
00615 except struct.error as se: self._check_types(se)
00616 except TypeError as te: self._check_types(te)
00617
00618 def deserialize_numpy(self, str, numpy):
00619 """
00620 unpack serialized message in str into this message instance using numpy for array types
00621 :param str: byte array of serialized message, ``str``
00622 :param numpy: numpy python module
00623 """
00624 try:
00625 if self.image is None:
00626 self.image = sensor_msgs.msg.Image()
00627 if self.info is None:
00628 self.info = sensor_msgs.msg.CameraInfo()
00629 if self.features is None:
00630 self.features = posedetection_msgs.msg.Feature0D()
00631 end = 0
00632 _x = self
00633 start = end
00634 end += 12
00635 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00636 start = end
00637 end += 4
00638 (length,) = _struct_I.unpack(str[start:end])
00639 start = end
00640 end += length
00641 if python3:
00642 self.image.header.frame_id = str[start:end].decode('utf-8')
00643 else:
00644 self.image.header.frame_id = str[start:end]
00645 _x = self
00646 start = end
00647 end += 8
00648 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00649 start = end
00650 end += 4
00651 (length,) = _struct_I.unpack(str[start:end])
00652 start = end
00653 end += length
00654 if python3:
00655 self.image.encoding = str[start:end].decode('utf-8')
00656 else:
00657 self.image.encoding = str[start:end]
00658 _x = self
00659 start = end
00660 end += 5
00661 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00662 start = end
00663 end += 4
00664 (length,) = _struct_I.unpack(str[start:end])
00665 start = end
00666 end += length
00667 if python3:
00668 self.image.data = str[start:end].decode('utf-8')
00669 else:
00670 self.image.data = str[start:end]
00671 _x = self
00672 start = end
00673 end += 12
00674 (_x.info.header.seq, _x.info.header.stamp.secs, _x.info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00675 start = end
00676 end += 4
00677 (length,) = _struct_I.unpack(str[start:end])
00678 start = end
00679 end += length
00680 if python3:
00681 self.info.header.frame_id = str[start:end].decode('utf-8')
00682 else:
00683 self.info.header.frame_id = str[start:end]
00684 _x = self
00685 start = end
00686 end += 8
00687 (_x.info.height, _x.info.width,) = _struct_2I.unpack(str[start:end])
00688 start = end
00689 end += 4
00690 (length,) = _struct_I.unpack(str[start:end])
00691 start = end
00692 end += length
00693 if python3:
00694 self.info.distortion_model = str[start:end].decode('utf-8')
00695 else:
00696 self.info.distortion_model = str[start:end]
00697 start = end
00698 end += 4
00699 (length,) = _struct_I.unpack(str[start:end])
00700 pattern = '<%sd'%length
00701 start = end
00702 end += struct.calcsize(pattern)
00703 self.info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00704 start = end
00705 end += 72
00706 self.info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00707 start = end
00708 end += 72
00709 self.info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00710 start = end
00711 end += 96
00712 self.info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
00713 _x = self
00714 start = end
00715 end += 37
00716 (_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])
00717 self.info.roi.do_rectify = bool(self.info.roi.do_rectify)
00718 start = end
00719 end += 4
00720 (length,) = _struct_I.unpack(str[start:end])
00721 start = end
00722 end += length
00723 if python3:
00724 self.features.header.frame_id = str[start:end].decode('utf-8')
00725 else:
00726 self.features.header.frame_id = str[start:end]
00727 start = end
00728 end += 4
00729 (length,) = _struct_I.unpack(str[start:end])
00730 pattern = '<%sf'%length
00731 start = end
00732 end += struct.calcsize(pattern)
00733 self.features.positions = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00734 start = end
00735 end += 4
00736 (length,) = _struct_I.unpack(str[start:end])
00737 pattern = '<%sf'%length
00738 start = end
00739 end += struct.calcsize(pattern)
00740 self.features.scales = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00741 start = end
00742 end += 4
00743 (length,) = _struct_I.unpack(str[start:end])
00744 pattern = '<%sf'%length
00745 start = end
00746 end += struct.calcsize(pattern)
00747 self.features.orientations = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00748 start = end
00749 end += 4
00750 (length,) = _struct_I.unpack(str[start:end])
00751 pattern = '<%sf'%length
00752 start = end
00753 end += struct.calcsize(pattern)
00754 self.features.confidences = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 pattern = '<%sf'%length
00759 start = end
00760 end += struct.calcsize(pattern)
00761 self.features.descriptors = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00762 start = end
00763 end += 4
00764 (self.features.descriptor_dim,) = _struct_i.unpack(str[start:end])
00765 start = end
00766 end += 4
00767 (length,) = _struct_I.unpack(str[start:end])
00768 start = end
00769 end += length
00770 if python3:
00771 self.features.type = str[start:end].decode('utf-8')
00772 else:
00773 self.features.type = str[start:end]
00774 return self
00775 except struct.error as e:
00776 raise genpy.DeserializationError(e)
00777
00778 _struct_I = genpy.struct_I
00779 _struct_6IB3I = struct.Struct("<6IB3I")
00780 _struct_12d = struct.Struct("<12d")
00781 _struct_i = struct.Struct("<i")
00782 _struct_9d = struct.Struct("<9d")
00783 _struct_BI = struct.Struct("<BI")
00784 _struct_3I = struct.Struct("<3I")
00785 _struct_2I = struct.Struct("<2I")