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