00001 """autogenerated by genpy from object_recognition_gui/ObjectRecognitionGuiActionGoal.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 arm_navigation_msgs.msg
00008 import actionlib_msgs.msg
00009 import geometry_msgs.msg
00010 import object_recognition_gui.msg
00011 import sensor_msgs.msg
00012 import genpy
00013 import std_msgs.msg
00014
00015 class ObjectRecognitionGuiActionGoal(genpy.Message):
00016 _md5sum = "e9351c4dd7bd646f1f371db4c7fd13af"
00017 _type = "object_recognition_gui/ObjectRecognitionGuiActionGoal"
00018 _has_header = True
00019 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00020
00021 Header header
00022 actionlib_msgs/GoalID goal_id
00023 ObjectRecognitionGuiGoal goal
00024
00025 ================================================================================
00026 MSG: std_msgs/Header
00027 # Standard metadata for higher-level stamped data types.
00028 # This is generally used to communicate timestamped data
00029 # in a particular coordinate frame.
00030 #
00031 # sequence ID: consecutively increasing ID
00032 uint32 seq
00033 #Two-integer timestamp that is expressed as:
00034 # * stamp.secs: seconds (stamp_secs) since epoch
00035 # * stamp.nsecs: nanoseconds since stamp_secs
00036 # time-handling sugar is provided by the client library
00037 time stamp
00038 #Frame this data is associated with
00039 # 0: no frame
00040 # 1: global frame
00041 string frame_id
00042
00043 ================================================================================
00044 MSG: actionlib_msgs/GoalID
00045 # The stamp should store the time at which this goal was requested.
00046 # It is used by an action server when it tries to preempt all
00047 # goals that were requested before a certain time
00048 time stamp
00049
00050 # The id provides a way to associate feedback and
00051 # result message with specific goal requests. The id
00052 # specified must be unique.
00053 string id
00054
00055
00056 ================================================================================
00057 MSG: object_recognition_gui/ObjectRecognitionGuiGoal
00058 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00059
00060 #the original sensor data (depth/disparity image)
00061 sensor_msgs/Image image
00062 sensor_msgs/CameraInfo camera_info
00063
00064 #list of mesh/pose hypotheses for each recognized point cluster
00065 ModelHypothesisList[] model_hypotheses
00066
00067 ================================================================================
00068 MSG: sensor_msgs/Image
00069 # This message contains an uncompressed image
00070 # (0, 0) is at top-left corner of image
00071 #
00072
00073 Header header # Header timestamp should be acquisition time of image
00074 # Header frame_id should be optical frame of camera
00075 # origin of frame should be optical center of cameara
00076 # +x should point to the right in the image
00077 # +y should point down in the image
00078 # +z should point into to plane of the image
00079 # If the frame_id here and the frame_id of the CameraInfo
00080 # message associated with the image conflict
00081 # the behavior is undefined
00082
00083 uint32 height # image height, that is, number of rows
00084 uint32 width # image width, that is, number of columns
00085
00086 # The legal values for encoding are in file src/image_encodings.cpp
00087 # If you want to standardize a new string format, join
00088 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00089
00090 string encoding # Encoding of pixels -- channel meaning, ordering, size
00091 # taken from the list of strings in src/image_encodings.cpp
00092
00093 uint8 is_bigendian # is this data bigendian?
00094 uint32 step # Full row length in bytes
00095 uint8[] data # actual matrix data, size is (step * rows)
00096
00097 ================================================================================
00098 MSG: sensor_msgs/CameraInfo
00099 # This message defines meta information for a camera. It should be in a
00100 # camera namespace on topic "camera_info" and accompanied by up to five
00101 # image topics named:
00102 #
00103 # image_raw - raw data from the camera driver, possibly Bayer encoded
00104 # image - monochrome, distorted
00105 # image_color - color, distorted
00106 # image_rect - monochrome, rectified
00107 # image_rect_color - color, rectified
00108 #
00109 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00110 # for producing the four processed image topics from image_raw and
00111 # camera_info. The meaning of the camera parameters are described in
00112 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00113 #
00114 # The image_geometry package provides a user-friendly interface to
00115 # common operations using this meta information. If you want to, e.g.,
00116 # project a 3d point into image coordinates, we strongly recommend
00117 # using image_geometry.
00118 #
00119 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00120 # zeroed out. In particular, clients may assume that K[0] == 0.0
00121 # indicates an uncalibrated camera.
00122
00123 #######################################################################
00124 # Image acquisition info #
00125 #######################################################################
00126
00127 # Time of image acquisition, camera coordinate frame ID
00128 Header header # Header timestamp should be acquisition time of image
00129 # Header frame_id should be optical frame of camera
00130 # origin of frame should be optical center of camera
00131 # +x should point to the right in the image
00132 # +y should point down in the image
00133 # +z should point into the plane of the image
00134
00135
00136 #######################################################################
00137 # Calibration Parameters #
00138 #######################################################################
00139 # These are fixed during camera calibration. Their values will be the #
00140 # same in all messages until the camera is recalibrated. Note that #
00141 # self-calibrating systems may "recalibrate" frequently. #
00142 # #
00143 # The internal parameters can be used to warp a raw (distorted) image #
00144 # to: #
00145 # 1. An undistorted image (requires D and K) #
00146 # 2. A rectified image (requires D, K, R) #
00147 # The projection matrix P projects 3D points into the rectified image.#
00148 #######################################################################
00149
00150 # The image dimensions with which the camera was calibrated. Normally
00151 # this will be the full camera resolution in pixels.
00152 uint32 height
00153 uint32 width
00154
00155 # The distortion model used. Supported models are listed in
00156 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00157 # simple model of radial and tangential distortion - is sufficent.
00158 string distortion_model
00159
00160 # The distortion parameters, size depending on the distortion model.
00161 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00162 float64[] D
00163
00164 # Intrinsic camera matrix for the raw (distorted) images.
00165 # [fx 0 cx]
00166 # K = [ 0 fy cy]
00167 # [ 0 0 1]
00168 # Projects 3D points in the camera coordinate frame to 2D pixel
00169 # coordinates using the focal lengths (fx, fy) and principal point
00170 # (cx, cy).
00171 float64[9] K # 3x3 row-major matrix
00172
00173 # Rectification matrix (stereo cameras only)
00174 # A rotation matrix aligning the camera coordinate system to the ideal
00175 # stereo image plane so that epipolar lines in both stereo images are
00176 # parallel.
00177 float64[9] R # 3x3 row-major matrix
00178
00179 # Projection/camera matrix
00180 # [fx' 0 cx' Tx]
00181 # P = [ 0 fy' cy' Ty]
00182 # [ 0 0 1 0]
00183 # By convention, this matrix specifies the intrinsic (camera) matrix
00184 # of the processed (rectified) image. That is, the left 3x3 portion
00185 # is the normal camera intrinsic matrix for the rectified image.
00186 # It projects 3D points in the camera coordinate frame to 2D pixel
00187 # coordinates using the focal lengths (fx', fy') and principal point
00188 # (cx', cy') - these may differ from the values in K.
00189 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00190 # also have R = the identity and P[1:3,1:3] = K.
00191 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00192 # position of the optical center of the second camera in the first
00193 # camera's frame. We assume Tz = 0 so both cameras are in the same
00194 # stereo image plane. The first camera always has Tx = Ty = 0. For
00195 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00196 # Tx = -fx' * B, where B is the baseline between the cameras.
00197 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00198 # the rectified image is given by:
00199 # [u v w]' = P * [X Y Z 1]'
00200 # x = u / w
00201 # y = v / w
00202 # This holds for both images of a stereo pair.
00203 float64[12] P # 3x4 row-major matrix
00204
00205
00206 #######################################################################
00207 # Operational Parameters #
00208 #######################################################################
00209 # These define the image region actually captured by the camera #
00210 # driver. Although they affect the geometry of the output image, they #
00211 # may be changed freely without recalibrating the camera. #
00212 #######################################################################
00213
00214 # Binning refers here to any camera setting which combines rectangular
00215 # neighborhoods of pixels into larger "super-pixels." It reduces the
00216 # resolution of the output image to
00217 # (width / binning_x) x (height / binning_y).
00218 # The default values binning_x = binning_y = 0 is considered the same
00219 # as binning_x = binning_y = 1 (no subsampling).
00220 uint32 binning_x
00221 uint32 binning_y
00222
00223 # Region of interest (subwindow of full camera resolution), given in
00224 # full resolution (unbinned) image coordinates. A particular ROI
00225 # always denotes the same window of pixels on the camera sensor,
00226 # regardless of binning settings.
00227 # The default setting of roi (all values 0) is considered the same as
00228 # full resolution (roi.width = width, roi.height = height).
00229 RegionOfInterest roi
00230
00231 ================================================================================
00232 MSG: sensor_msgs/RegionOfInterest
00233 # This message is used to specify a region of interest within an image.
00234 #
00235 # When used to specify the ROI setting of the camera when the image was
00236 # taken, the height and width fields should either match the height and
00237 # width fields for the associated image; or height = width = 0
00238 # indicates that the full resolution image was captured.
00239
00240 uint32 x_offset # Leftmost pixel of the ROI
00241 # (0 if the ROI includes the left edge of the image)
00242 uint32 y_offset # Topmost pixel of the ROI
00243 # (0 if the ROI includes the top edge of the image)
00244 uint32 height # Height of ROI
00245 uint32 width # Width of ROI
00246
00247 # True if a distinct rectified ROI should be calculated from the "raw"
00248 # ROI in this message. Typically this should be False if the full image
00249 # is captured (ROI not used), and True if a subwindow is captured (ROI
00250 # used).
00251 bool do_rectify
00252
00253 ================================================================================
00254 MSG: object_recognition_gui/ModelHypothesisList
00255 ModelHypothesis[] hypotheses
00256
00257 #initial guess if this can be a correct recognition result at all
00258 bool accept
00259 ================================================================================
00260 MSG: object_recognition_gui/ModelHypothesis
00261 #describes a hypothesis about a recognized object (mesh+pose)
00262
00263 arm_navigation_msgs/Shape mesh
00264 geometry_msgs/PoseStamped pose
00265
00266 ================================================================================
00267 MSG: arm_navigation_msgs/Shape
00268 byte SPHERE=0
00269 byte BOX=1
00270 byte CYLINDER=2
00271 byte MESH=3
00272
00273 byte type
00274
00275
00276 #### define sphere, box, cylinder ####
00277 # the origin of each shape is considered at the shape's center
00278
00279 # for sphere
00280 # radius := dimensions[0]
00281
00282 # for cylinder
00283 # radius := dimensions[0]
00284 # length := dimensions[1]
00285 # the length is along the Z axis
00286
00287 # for box
00288 # size_x := dimensions[0]
00289 # size_y := dimensions[1]
00290 # size_z := dimensions[2]
00291 float64[] dimensions
00292
00293
00294 #### define mesh ####
00295
00296 # list of triangles; triangle k is defined by tre vertices located
00297 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00298 int32[] triangles
00299 geometry_msgs/Point[] vertices
00300
00301 ================================================================================
00302 MSG: geometry_msgs/Point
00303 # This contains the position of a point in free space
00304 float64 x
00305 float64 y
00306 float64 z
00307
00308 ================================================================================
00309 MSG: geometry_msgs/PoseStamped
00310 # A Pose with reference coordinate frame and timestamp
00311 Header header
00312 Pose pose
00313
00314 ================================================================================
00315 MSG: geometry_msgs/Pose
00316 # A representation of pose in free space, composed of postion and orientation.
00317 Point position
00318 Quaternion orientation
00319
00320 ================================================================================
00321 MSG: geometry_msgs/Quaternion
00322 # This represents an orientation in free space in quaternion form.
00323
00324 float64 x
00325 float64 y
00326 float64 z
00327 float64 w
00328
00329 """
00330 __slots__ = ['header','goal_id','goal']
00331 _slot_types = ['std_msgs/Header','actionlib_msgs/GoalID','object_recognition_gui/ObjectRecognitionGuiGoal']
00332
00333 def __init__(self, *args, **kwds):
00334 """
00335 Constructor. Any message fields that are implicitly/explicitly
00336 set to None will be assigned a default value. The recommend
00337 use is keyword arguments as this is more robust to future message
00338 changes. You cannot mix in-order arguments and keyword arguments.
00339
00340 The available fields are:
00341 header,goal_id,goal
00342
00343 :param args: complete set of field values, in .msg order
00344 :param kwds: use keyword arguments corresponding to message field names
00345 to set specific fields.
00346 """
00347 if args or kwds:
00348 super(ObjectRecognitionGuiActionGoal, self).__init__(*args, **kwds)
00349
00350 if self.header is None:
00351 self.header = std_msgs.msg.Header()
00352 if self.goal_id is None:
00353 self.goal_id = actionlib_msgs.msg.GoalID()
00354 if self.goal is None:
00355 self.goal = object_recognition_gui.msg.ObjectRecognitionGuiGoal()
00356 else:
00357 self.header = std_msgs.msg.Header()
00358 self.goal_id = actionlib_msgs.msg.GoalID()
00359 self.goal = object_recognition_gui.msg.ObjectRecognitionGuiGoal()
00360
00361 def _get_types(self):
00362 """
00363 internal API method
00364 """
00365 return self._slot_types
00366
00367 def serialize(self, buff):
00368 """
00369 serialize message into buffer
00370 :param buff: buffer, ``StringIO``
00371 """
00372 try:
00373 _x = self
00374 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00375 _x = self.header.frame_id
00376 length = len(_x)
00377 if python3 or type(_x) == unicode:
00378 _x = _x.encode('utf-8')
00379 length = len(_x)
00380 buff.write(struct.pack('<I%ss'%length, length, _x))
00381 _x = self
00382 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00383 _x = self.goal_id.id
00384 length = len(_x)
00385 if python3 or type(_x) == unicode:
00386 _x = _x.encode('utf-8')
00387 length = len(_x)
00388 buff.write(struct.pack('<I%ss'%length, length, _x))
00389 _x = self
00390 buff.write(_struct_3I.pack(_x.goal.image.header.seq, _x.goal.image.header.stamp.secs, _x.goal.image.header.stamp.nsecs))
00391 _x = self.goal.image.header.frame_id
00392 length = len(_x)
00393 if python3 or type(_x) == unicode:
00394 _x = _x.encode('utf-8')
00395 length = len(_x)
00396 buff.write(struct.pack('<I%ss'%length, length, _x))
00397 _x = self
00398 buff.write(_struct_2I.pack(_x.goal.image.height, _x.goal.image.width))
00399 _x = self.goal.image.encoding
00400 length = len(_x)
00401 if python3 or type(_x) == unicode:
00402 _x = _x.encode('utf-8')
00403 length = len(_x)
00404 buff.write(struct.pack('<I%ss'%length, length, _x))
00405 _x = self
00406 buff.write(_struct_BI.pack(_x.goal.image.is_bigendian, _x.goal.image.step))
00407 _x = self.goal.image.data
00408 length = len(_x)
00409
00410 if type(_x) in [list, tuple]:
00411 buff.write(struct.pack('<I%sB'%length, length, *_x))
00412 else:
00413 buff.write(struct.pack('<I%ss'%length, length, _x))
00414 _x = self
00415 buff.write(_struct_3I.pack(_x.goal.camera_info.header.seq, _x.goal.camera_info.header.stamp.secs, _x.goal.camera_info.header.stamp.nsecs))
00416 _x = self.goal.camera_info.header.frame_id
00417 length = len(_x)
00418 if python3 or type(_x) == unicode:
00419 _x = _x.encode('utf-8')
00420 length = len(_x)
00421 buff.write(struct.pack('<I%ss'%length, length, _x))
00422 _x = self
00423 buff.write(_struct_2I.pack(_x.goal.camera_info.height, _x.goal.camera_info.width))
00424 _x = self.goal.camera_info.distortion_model
00425 length = len(_x)
00426 if python3 or type(_x) == unicode:
00427 _x = _x.encode('utf-8')
00428 length = len(_x)
00429 buff.write(struct.pack('<I%ss'%length, length, _x))
00430 length = len(self.goal.camera_info.D)
00431 buff.write(_struct_I.pack(length))
00432 pattern = '<%sd'%length
00433 buff.write(struct.pack(pattern, *self.goal.camera_info.D))
00434 buff.write(_struct_9d.pack(*self.goal.camera_info.K))
00435 buff.write(_struct_9d.pack(*self.goal.camera_info.R))
00436 buff.write(_struct_12d.pack(*self.goal.camera_info.P))
00437 _x = self
00438 buff.write(_struct_6IB.pack(_x.goal.camera_info.binning_x, _x.goal.camera_info.binning_y, _x.goal.camera_info.roi.x_offset, _x.goal.camera_info.roi.y_offset, _x.goal.camera_info.roi.height, _x.goal.camera_info.roi.width, _x.goal.camera_info.roi.do_rectify))
00439 length = len(self.goal.model_hypotheses)
00440 buff.write(_struct_I.pack(length))
00441 for val1 in self.goal.model_hypotheses:
00442 length = len(val1.hypotheses)
00443 buff.write(_struct_I.pack(length))
00444 for val2 in val1.hypotheses:
00445 _v1 = val2.mesh
00446 buff.write(_struct_b.pack(_v1.type))
00447 length = len(_v1.dimensions)
00448 buff.write(_struct_I.pack(length))
00449 pattern = '<%sd'%length
00450 buff.write(struct.pack(pattern, *_v1.dimensions))
00451 length = len(_v1.triangles)
00452 buff.write(_struct_I.pack(length))
00453 pattern = '<%si'%length
00454 buff.write(struct.pack(pattern, *_v1.triangles))
00455 length = len(_v1.vertices)
00456 buff.write(_struct_I.pack(length))
00457 for val4 in _v1.vertices:
00458 _x = val4
00459 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00460 _v2 = val2.pose
00461 _v3 = _v2.header
00462 buff.write(_struct_I.pack(_v3.seq))
00463 _v4 = _v3.stamp
00464 _x = _v4
00465 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00466 _x = _v3.frame_id
00467 length = len(_x)
00468 if python3 or type(_x) == unicode:
00469 _x = _x.encode('utf-8')
00470 length = len(_x)
00471 buff.write(struct.pack('<I%ss'%length, length, _x))
00472 _v5 = _v2.pose
00473 _v6 = _v5.position
00474 _x = _v6
00475 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00476 _v7 = _v5.orientation
00477 _x = _v7
00478 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00479 buff.write(_struct_B.pack(val1.accept))
00480 except struct.error as se: self._check_types(se)
00481 except TypeError as te: self._check_types(te)
00482
00483 def deserialize(self, str):
00484 """
00485 unpack serialized message in str into this message instance
00486 :param str: byte array of serialized message, ``str``
00487 """
00488 try:
00489 if self.header is None:
00490 self.header = std_msgs.msg.Header()
00491 if self.goal_id is None:
00492 self.goal_id = actionlib_msgs.msg.GoalID()
00493 if self.goal is None:
00494 self.goal = object_recognition_gui.msg.ObjectRecognitionGuiGoal()
00495 end = 0
00496 _x = self
00497 start = end
00498 end += 12
00499 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00500 start = end
00501 end += 4
00502 (length,) = _struct_I.unpack(str[start:end])
00503 start = end
00504 end += length
00505 if python3:
00506 self.header.frame_id = str[start:end].decode('utf-8')
00507 else:
00508 self.header.frame_id = str[start:end]
00509 _x = self
00510 start = end
00511 end += 8
00512 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00513 start = end
00514 end += 4
00515 (length,) = _struct_I.unpack(str[start:end])
00516 start = end
00517 end += length
00518 if python3:
00519 self.goal_id.id = str[start:end].decode('utf-8')
00520 else:
00521 self.goal_id.id = str[start:end]
00522 _x = self
00523 start = end
00524 end += 12
00525 (_x.goal.image.header.seq, _x.goal.image.header.stamp.secs, _x.goal.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00526 start = end
00527 end += 4
00528 (length,) = _struct_I.unpack(str[start:end])
00529 start = end
00530 end += length
00531 if python3:
00532 self.goal.image.header.frame_id = str[start:end].decode('utf-8')
00533 else:
00534 self.goal.image.header.frame_id = str[start:end]
00535 _x = self
00536 start = end
00537 end += 8
00538 (_x.goal.image.height, _x.goal.image.width,) = _struct_2I.unpack(str[start:end])
00539 start = end
00540 end += 4
00541 (length,) = _struct_I.unpack(str[start:end])
00542 start = end
00543 end += length
00544 if python3:
00545 self.goal.image.encoding = str[start:end].decode('utf-8')
00546 else:
00547 self.goal.image.encoding = str[start:end]
00548 _x = self
00549 start = end
00550 end += 5
00551 (_x.goal.image.is_bigendian, _x.goal.image.step,) = _struct_BI.unpack(str[start:end])
00552 start = end
00553 end += 4
00554 (length,) = _struct_I.unpack(str[start:end])
00555 start = end
00556 end += length
00557 if python3:
00558 self.goal.image.data = str[start:end].decode('utf-8')
00559 else:
00560 self.goal.image.data = str[start:end]
00561 _x = self
00562 start = end
00563 end += 12
00564 (_x.goal.camera_info.header.seq, _x.goal.camera_info.header.stamp.secs, _x.goal.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00565 start = end
00566 end += 4
00567 (length,) = _struct_I.unpack(str[start:end])
00568 start = end
00569 end += length
00570 if python3:
00571 self.goal.camera_info.header.frame_id = str[start:end].decode('utf-8')
00572 else:
00573 self.goal.camera_info.header.frame_id = str[start:end]
00574 _x = self
00575 start = end
00576 end += 8
00577 (_x.goal.camera_info.height, _x.goal.camera_info.width,) = _struct_2I.unpack(str[start:end])
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 start = end
00582 end += length
00583 if python3:
00584 self.goal.camera_info.distortion_model = str[start:end].decode('utf-8')
00585 else:
00586 self.goal.camera_info.distortion_model = str[start:end]
00587 start = end
00588 end += 4
00589 (length,) = _struct_I.unpack(str[start:end])
00590 pattern = '<%sd'%length
00591 start = end
00592 end += struct.calcsize(pattern)
00593 self.goal.camera_info.D = struct.unpack(pattern, str[start:end])
00594 start = end
00595 end += 72
00596 self.goal.camera_info.K = _struct_9d.unpack(str[start:end])
00597 start = end
00598 end += 72
00599 self.goal.camera_info.R = _struct_9d.unpack(str[start:end])
00600 start = end
00601 end += 96
00602 self.goal.camera_info.P = _struct_12d.unpack(str[start:end])
00603 _x = self
00604 start = end
00605 end += 25
00606 (_x.goal.camera_info.binning_x, _x.goal.camera_info.binning_y, _x.goal.camera_info.roi.x_offset, _x.goal.camera_info.roi.y_offset, _x.goal.camera_info.roi.height, _x.goal.camera_info.roi.width, _x.goal.camera_info.roi.do_rectify,) = _struct_6IB.unpack(str[start:end])
00607 self.goal.camera_info.roi.do_rectify = bool(self.goal.camera_info.roi.do_rectify)
00608 start = end
00609 end += 4
00610 (length,) = _struct_I.unpack(str[start:end])
00611 self.goal.model_hypotheses = []
00612 for i in range(0, length):
00613 val1 = object_recognition_gui.msg.ModelHypothesisList()
00614 start = end
00615 end += 4
00616 (length,) = _struct_I.unpack(str[start:end])
00617 val1.hypotheses = []
00618 for i in range(0, length):
00619 val2 = object_recognition_gui.msg.ModelHypothesis()
00620 _v8 = val2.mesh
00621 start = end
00622 end += 1
00623 (_v8.type,) = _struct_b.unpack(str[start:end])
00624 start = end
00625 end += 4
00626 (length,) = _struct_I.unpack(str[start:end])
00627 pattern = '<%sd'%length
00628 start = end
00629 end += struct.calcsize(pattern)
00630 _v8.dimensions = struct.unpack(pattern, str[start:end])
00631 start = end
00632 end += 4
00633 (length,) = _struct_I.unpack(str[start:end])
00634 pattern = '<%si'%length
00635 start = end
00636 end += struct.calcsize(pattern)
00637 _v8.triangles = struct.unpack(pattern, str[start:end])
00638 start = end
00639 end += 4
00640 (length,) = _struct_I.unpack(str[start:end])
00641 _v8.vertices = []
00642 for i in range(0, length):
00643 val4 = geometry_msgs.msg.Point()
00644 _x = val4
00645 start = end
00646 end += 24
00647 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00648 _v8.vertices.append(val4)
00649 _v9 = val2.pose
00650 _v10 = _v9.header
00651 start = end
00652 end += 4
00653 (_v10.seq,) = _struct_I.unpack(str[start:end])
00654 _v11 = _v10.stamp
00655 _x = _v11
00656 start = end
00657 end += 8
00658 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00659 start = end
00660 end += 4
00661 (length,) = _struct_I.unpack(str[start:end])
00662 start = end
00663 end += length
00664 if python3:
00665 _v10.frame_id = str[start:end].decode('utf-8')
00666 else:
00667 _v10.frame_id = str[start:end]
00668 _v12 = _v9.pose
00669 _v13 = _v12.position
00670 _x = _v13
00671 start = end
00672 end += 24
00673 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00674 _v14 = _v12.orientation
00675 _x = _v14
00676 start = end
00677 end += 32
00678 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00679 val1.hypotheses.append(val2)
00680 start = end
00681 end += 1
00682 (val1.accept,) = _struct_B.unpack(str[start:end])
00683 val1.accept = bool(val1.accept)
00684 self.goal.model_hypotheses.append(val1)
00685 return self
00686 except struct.error as e:
00687 raise genpy.DeserializationError(e)
00688
00689
00690 def serialize_numpy(self, buff, numpy):
00691 """
00692 serialize message with numpy array types into buffer
00693 :param buff: buffer, ``StringIO``
00694 :param numpy: numpy python module
00695 """
00696 try:
00697 _x = self
00698 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00699 _x = self.header.frame_id
00700 length = len(_x)
00701 if python3 or type(_x) == unicode:
00702 _x = _x.encode('utf-8')
00703 length = len(_x)
00704 buff.write(struct.pack('<I%ss'%length, length, _x))
00705 _x = self
00706 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00707 _x = self.goal_id.id
00708 length = len(_x)
00709 if python3 or type(_x) == unicode:
00710 _x = _x.encode('utf-8')
00711 length = len(_x)
00712 buff.write(struct.pack('<I%ss'%length, length, _x))
00713 _x = self
00714 buff.write(_struct_3I.pack(_x.goal.image.header.seq, _x.goal.image.header.stamp.secs, _x.goal.image.header.stamp.nsecs))
00715 _x = self.goal.image.header.frame_id
00716 length = len(_x)
00717 if python3 or type(_x) == unicode:
00718 _x = _x.encode('utf-8')
00719 length = len(_x)
00720 buff.write(struct.pack('<I%ss'%length, length, _x))
00721 _x = self
00722 buff.write(_struct_2I.pack(_x.goal.image.height, _x.goal.image.width))
00723 _x = self.goal.image.encoding
00724 length = len(_x)
00725 if python3 or type(_x) == unicode:
00726 _x = _x.encode('utf-8')
00727 length = len(_x)
00728 buff.write(struct.pack('<I%ss'%length, length, _x))
00729 _x = self
00730 buff.write(_struct_BI.pack(_x.goal.image.is_bigendian, _x.goal.image.step))
00731 _x = self.goal.image.data
00732 length = len(_x)
00733
00734 if type(_x) in [list, tuple]:
00735 buff.write(struct.pack('<I%sB'%length, length, *_x))
00736 else:
00737 buff.write(struct.pack('<I%ss'%length, length, _x))
00738 _x = self
00739 buff.write(_struct_3I.pack(_x.goal.camera_info.header.seq, _x.goal.camera_info.header.stamp.secs, _x.goal.camera_info.header.stamp.nsecs))
00740 _x = self.goal.camera_info.header.frame_id
00741 length = len(_x)
00742 if python3 or type(_x) == unicode:
00743 _x = _x.encode('utf-8')
00744 length = len(_x)
00745 buff.write(struct.pack('<I%ss'%length, length, _x))
00746 _x = self
00747 buff.write(_struct_2I.pack(_x.goal.camera_info.height, _x.goal.camera_info.width))
00748 _x = self.goal.camera_info.distortion_model
00749 length = len(_x)
00750 if python3 or type(_x) == unicode:
00751 _x = _x.encode('utf-8')
00752 length = len(_x)
00753 buff.write(struct.pack('<I%ss'%length, length, _x))
00754 length = len(self.goal.camera_info.D)
00755 buff.write(_struct_I.pack(length))
00756 pattern = '<%sd'%length
00757 buff.write(self.goal.camera_info.D.tostring())
00758 buff.write(self.goal.camera_info.K.tostring())
00759 buff.write(self.goal.camera_info.R.tostring())
00760 buff.write(self.goal.camera_info.P.tostring())
00761 _x = self
00762 buff.write(_struct_6IB.pack(_x.goal.camera_info.binning_x, _x.goal.camera_info.binning_y, _x.goal.camera_info.roi.x_offset, _x.goal.camera_info.roi.y_offset, _x.goal.camera_info.roi.height, _x.goal.camera_info.roi.width, _x.goal.camera_info.roi.do_rectify))
00763 length = len(self.goal.model_hypotheses)
00764 buff.write(_struct_I.pack(length))
00765 for val1 in self.goal.model_hypotheses:
00766 length = len(val1.hypotheses)
00767 buff.write(_struct_I.pack(length))
00768 for val2 in val1.hypotheses:
00769 _v15 = val2.mesh
00770 buff.write(_struct_b.pack(_v15.type))
00771 length = len(_v15.dimensions)
00772 buff.write(_struct_I.pack(length))
00773 pattern = '<%sd'%length
00774 buff.write(_v15.dimensions.tostring())
00775 length = len(_v15.triangles)
00776 buff.write(_struct_I.pack(length))
00777 pattern = '<%si'%length
00778 buff.write(_v15.triangles.tostring())
00779 length = len(_v15.vertices)
00780 buff.write(_struct_I.pack(length))
00781 for val4 in _v15.vertices:
00782 _x = val4
00783 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00784 _v16 = val2.pose
00785 _v17 = _v16.header
00786 buff.write(_struct_I.pack(_v17.seq))
00787 _v18 = _v17.stamp
00788 _x = _v18
00789 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00790 _x = _v17.frame_id
00791 length = len(_x)
00792 if python3 or type(_x) == unicode:
00793 _x = _x.encode('utf-8')
00794 length = len(_x)
00795 buff.write(struct.pack('<I%ss'%length, length, _x))
00796 _v19 = _v16.pose
00797 _v20 = _v19.position
00798 _x = _v20
00799 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00800 _v21 = _v19.orientation
00801 _x = _v21
00802 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00803 buff.write(_struct_B.pack(val1.accept))
00804 except struct.error as se: self._check_types(se)
00805 except TypeError as te: self._check_types(te)
00806
00807 def deserialize_numpy(self, str, numpy):
00808 """
00809 unpack serialized message in str into this message instance using numpy for array types
00810 :param str: byte array of serialized message, ``str``
00811 :param numpy: numpy python module
00812 """
00813 try:
00814 if self.header is None:
00815 self.header = std_msgs.msg.Header()
00816 if self.goal_id is None:
00817 self.goal_id = actionlib_msgs.msg.GoalID()
00818 if self.goal is None:
00819 self.goal = object_recognition_gui.msg.ObjectRecognitionGuiGoal()
00820 end = 0
00821 _x = self
00822 start = end
00823 end += 12
00824 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00825 start = end
00826 end += 4
00827 (length,) = _struct_I.unpack(str[start:end])
00828 start = end
00829 end += length
00830 if python3:
00831 self.header.frame_id = str[start:end].decode('utf-8')
00832 else:
00833 self.header.frame_id = str[start:end]
00834 _x = self
00835 start = end
00836 end += 8
00837 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00838 start = end
00839 end += 4
00840 (length,) = _struct_I.unpack(str[start:end])
00841 start = end
00842 end += length
00843 if python3:
00844 self.goal_id.id = str[start:end].decode('utf-8')
00845 else:
00846 self.goal_id.id = str[start:end]
00847 _x = self
00848 start = end
00849 end += 12
00850 (_x.goal.image.header.seq, _x.goal.image.header.stamp.secs, _x.goal.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00851 start = end
00852 end += 4
00853 (length,) = _struct_I.unpack(str[start:end])
00854 start = end
00855 end += length
00856 if python3:
00857 self.goal.image.header.frame_id = str[start:end].decode('utf-8')
00858 else:
00859 self.goal.image.header.frame_id = str[start:end]
00860 _x = self
00861 start = end
00862 end += 8
00863 (_x.goal.image.height, _x.goal.image.width,) = _struct_2I.unpack(str[start:end])
00864 start = end
00865 end += 4
00866 (length,) = _struct_I.unpack(str[start:end])
00867 start = end
00868 end += length
00869 if python3:
00870 self.goal.image.encoding = str[start:end].decode('utf-8')
00871 else:
00872 self.goal.image.encoding = str[start:end]
00873 _x = self
00874 start = end
00875 end += 5
00876 (_x.goal.image.is_bigendian, _x.goal.image.step,) = _struct_BI.unpack(str[start:end])
00877 start = end
00878 end += 4
00879 (length,) = _struct_I.unpack(str[start:end])
00880 start = end
00881 end += length
00882 if python3:
00883 self.goal.image.data = str[start:end].decode('utf-8')
00884 else:
00885 self.goal.image.data = str[start:end]
00886 _x = self
00887 start = end
00888 end += 12
00889 (_x.goal.camera_info.header.seq, _x.goal.camera_info.header.stamp.secs, _x.goal.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00890 start = end
00891 end += 4
00892 (length,) = _struct_I.unpack(str[start:end])
00893 start = end
00894 end += length
00895 if python3:
00896 self.goal.camera_info.header.frame_id = str[start:end].decode('utf-8')
00897 else:
00898 self.goal.camera_info.header.frame_id = str[start:end]
00899 _x = self
00900 start = end
00901 end += 8
00902 (_x.goal.camera_info.height, _x.goal.camera_info.width,) = _struct_2I.unpack(str[start:end])
00903 start = end
00904 end += 4
00905 (length,) = _struct_I.unpack(str[start:end])
00906 start = end
00907 end += length
00908 if python3:
00909 self.goal.camera_info.distortion_model = str[start:end].decode('utf-8')
00910 else:
00911 self.goal.camera_info.distortion_model = str[start:end]
00912 start = end
00913 end += 4
00914 (length,) = _struct_I.unpack(str[start:end])
00915 pattern = '<%sd'%length
00916 start = end
00917 end += struct.calcsize(pattern)
00918 self.goal.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00919 start = end
00920 end += 72
00921 self.goal.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00922 start = end
00923 end += 72
00924 self.goal.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00925 start = end
00926 end += 96
00927 self.goal.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
00928 _x = self
00929 start = end
00930 end += 25
00931 (_x.goal.camera_info.binning_x, _x.goal.camera_info.binning_y, _x.goal.camera_info.roi.x_offset, _x.goal.camera_info.roi.y_offset, _x.goal.camera_info.roi.height, _x.goal.camera_info.roi.width, _x.goal.camera_info.roi.do_rectify,) = _struct_6IB.unpack(str[start:end])
00932 self.goal.camera_info.roi.do_rectify = bool(self.goal.camera_info.roi.do_rectify)
00933 start = end
00934 end += 4
00935 (length,) = _struct_I.unpack(str[start:end])
00936 self.goal.model_hypotheses = []
00937 for i in range(0, length):
00938 val1 = object_recognition_gui.msg.ModelHypothesisList()
00939 start = end
00940 end += 4
00941 (length,) = _struct_I.unpack(str[start:end])
00942 val1.hypotheses = []
00943 for i in range(0, length):
00944 val2 = object_recognition_gui.msg.ModelHypothesis()
00945 _v22 = val2.mesh
00946 start = end
00947 end += 1
00948 (_v22.type,) = _struct_b.unpack(str[start:end])
00949 start = end
00950 end += 4
00951 (length,) = _struct_I.unpack(str[start:end])
00952 pattern = '<%sd'%length
00953 start = end
00954 end += struct.calcsize(pattern)
00955 _v22.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00956 start = end
00957 end += 4
00958 (length,) = _struct_I.unpack(str[start:end])
00959 pattern = '<%si'%length
00960 start = end
00961 end += struct.calcsize(pattern)
00962 _v22.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00963 start = end
00964 end += 4
00965 (length,) = _struct_I.unpack(str[start:end])
00966 _v22.vertices = []
00967 for i in range(0, length):
00968 val4 = geometry_msgs.msg.Point()
00969 _x = val4
00970 start = end
00971 end += 24
00972 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00973 _v22.vertices.append(val4)
00974 _v23 = val2.pose
00975 _v24 = _v23.header
00976 start = end
00977 end += 4
00978 (_v24.seq,) = _struct_I.unpack(str[start:end])
00979 _v25 = _v24.stamp
00980 _x = _v25
00981 start = end
00982 end += 8
00983 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00984 start = end
00985 end += 4
00986 (length,) = _struct_I.unpack(str[start:end])
00987 start = end
00988 end += length
00989 if python3:
00990 _v24.frame_id = str[start:end].decode('utf-8')
00991 else:
00992 _v24.frame_id = str[start:end]
00993 _v26 = _v23.pose
00994 _v27 = _v26.position
00995 _x = _v27
00996 start = end
00997 end += 24
00998 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00999 _v28 = _v26.orientation
01000 _x = _v28
01001 start = end
01002 end += 32
01003 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01004 val1.hypotheses.append(val2)
01005 start = end
01006 end += 1
01007 (val1.accept,) = _struct_B.unpack(str[start:end])
01008 val1.accept = bool(val1.accept)
01009 self.goal.model_hypotheses.append(val1)
01010 return self
01011 except struct.error as e:
01012 raise genpy.DeserializationError(e)
01013
01014 _struct_I = genpy.struct_I
01015 _struct_6IB = struct.Struct("<6IB")
01016 _struct_b = struct.Struct("<b")
01017 _struct_12d = struct.Struct("<12d")
01018 _struct_9d = struct.Struct("<9d")
01019 _struct_BI = struct.Struct("<BI")
01020 _struct_3I = struct.Struct("<3I")
01021 _struct_B = struct.Struct("<B")
01022 _struct_4d = struct.Struct("<4d")
01023 _struct_2I = struct.Struct("<2I")
01024 _struct_3d = struct.Struct("<3d")