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