00001 """autogenerated by genpy from interactive_perception_msgs/ObjectSegmentationGuiAction.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 tabletop_object_detector.msg
00008 import interactive_perception_msgs.msg
00009 import actionlib_msgs.msg
00010 import geometry_msgs.msg
00011 import shape_msgs.msg
00012 import stereo_msgs.msg
00013 import sensor_msgs.msg
00014 import genpy
00015 import std_msgs.msg
00016
00017 class ObjectSegmentationGuiAction(genpy.Message):
00018 _md5sum = "a27e9ddbd8daac45a258da8bcf472282"
00019 _type = "interactive_perception_msgs/ObjectSegmentationGuiAction"
00020 _has_header = False
00021 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00022
00023 ObjectSegmentationGuiActionGoal action_goal
00024 ObjectSegmentationGuiActionResult action_result
00025 ObjectSegmentationGuiActionFeedback action_feedback
00026
00027 ================================================================================
00028 MSG: interactive_perception_msgs/ObjectSegmentationGuiActionGoal
00029 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00030
00031 Header header
00032 actionlib_msgs/GoalID goal_id
00033 ObjectSegmentationGuiGoal goal
00034
00035 ================================================================================
00036 MSG: std_msgs/Header
00037 # Standard metadata for higher-level stamped data types.
00038 # This is generally used to communicate timestamped data
00039 # in a particular coordinate frame.
00040 #
00041 # sequence ID: consecutively increasing ID
00042 uint32 seq
00043 #Two-integer timestamp that is expressed as:
00044 # * stamp.secs: seconds (stamp_secs) since epoch
00045 # * stamp.nsecs: nanoseconds since stamp_secs
00046 # time-handling sugar is provided by the client library
00047 time stamp
00048 #Frame this data is associated with
00049 # 0: no frame
00050 # 1: global frame
00051 string frame_id
00052
00053 ================================================================================
00054 MSG: actionlib_msgs/GoalID
00055 # The stamp should store the time at which this goal was requested.
00056 # It is used by an action server when it tries to preempt all
00057 # goals that were requested before a certain time
00058 time stamp
00059
00060 # The id provides a way to associate feedback and
00061 # result message with specific goal requests. The id
00062 # specified must be unique.
00063 string id
00064
00065
00066 ================================================================================
00067 MSG: interactive_perception_msgs/ObjectSegmentationGuiGoal
00068 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00069 sensor_msgs/Image image
00070 sensor_msgs/CameraInfo camera_info
00071 sensor_msgs/Image wide_field
00072 sensor_msgs/CameraInfo wide_camera_info
00073
00074 sensor_msgs/PointCloud2 point_cloud
00075 stereo_msgs/DisparityImage disparity_image
00076
00077
00078 ================================================================================
00079 MSG: sensor_msgs/Image
00080 # This message contains an uncompressed image
00081 # (0, 0) is at top-left corner of image
00082 #
00083
00084 Header header # Header timestamp should be acquisition time of image
00085 # Header frame_id should be optical frame of camera
00086 # origin of frame should be optical center of cameara
00087 # +x should point to the right in the image
00088 # +y should point down in the image
00089 # +z should point into to plane of the image
00090 # If the frame_id here and the frame_id of the CameraInfo
00091 # message associated with the image conflict
00092 # the behavior is undefined
00093
00094 uint32 height # image height, that is, number of rows
00095 uint32 width # image width, that is, number of columns
00096
00097 # The legal values for encoding are in file src/image_encodings.cpp
00098 # If you want to standardize a new string format, join
00099 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00100
00101 string encoding # Encoding of pixels -- channel meaning, ordering, size
00102 # taken from the list of strings in include/sensor_msgs/image_encodings.h
00103
00104 uint8 is_bigendian # is this data bigendian?
00105 uint32 step # Full row length in bytes
00106 uint8[] data # actual matrix data, size is (step * rows)
00107
00108 ================================================================================
00109 MSG: sensor_msgs/CameraInfo
00110 # This message defines meta information for a camera. It should be in a
00111 # camera namespace on topic "camera_info" and accompanied by up to five
00112 # image topics named:
00113 #
00114 # image_raw - raw data from the camera driver, possibly Bayer encoded
00115 # image - monochrome, distorted
00116 # image_color - color, distorted
00117 # image_rect - monochrome, rectified
00118 # image_rect_color - color, rectified
00119 #
00120 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00121 # for producing the four processed image topics from image_raw and
00122 # camera_info. The meaning of the camera parameters are described in
00123 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00124 #
00125 # The image_geometry package provides a user-friendly interface to
00126 # common operations using this meta information. If you want to, e.g.,
00127 # project a 3d point into image coordinates, we strongly recommend
00128 # using image_geometry.
00129 #
00130 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00131 # zeroed out. In particular, clients may assume that K[0] == 0.0
00132 # indicates an uncalibrated camera.
00133
00134 #######################################################################
00135 # Image acquisition info #
00136 #######################################################################
00137
00138 # Time of image acquisition, camera coordinate frame ID
00139 Header header # Header timestamp should be acquisition time of image
00140 # Header frame_id should be optical frame of camera
00141 # origin of frame should be optical center of camera
00142 # +x should point to the right in the image
00143 # +y should point down in the image
00144 # +z should point into the plane of the image
00145
00146
00147 #######################################################################
00148 # Calibration Parameters #
00149 #######################################################################
00150 # These are fixed during camera calibration. Their values will be the #
00151 # same in all messages until the camera is recalibrated. Note that #
00152 # self-calibrating systems may "recalibrate" frequently. #
00153 # #
00154 # The internal parameters can be used to warp a raw (distorted) image #
00155 # to: #
00156 # 1. An undistorted image (requires D and K) #
00157 # 2. A rectified image (requires D, K, R) #
00158 # The projection matrix P projects 3D points into the rectified image.#
00159 #######################################################################
00160
00161 # The image dimensions with which the camera was calibrated. Normally
00162 # this will be the full camera resolution in pixels.
00163 uint32 height
00164 uint32 width
00165
00166 # The distortion model used. Supported models are listed in
00167 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00168 # simple model of radial and tangential distortion - is sufficent.
00169 string distortion_model
00170
00171 # The distortion parameters, size depending on the distortion model.
00172 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00173 float64[] D
00174
00175 # Intrinsic camera matrix for the raw (distorted) images.
00176 # [fx 0 cx]
00177 # K = [ 0 fy cy]
00178 # [ 0 0 1]
00179 # Projects 3D points in the camera coordinate frame to 2D pixel
00180 # coordinates using the focal lengths (fx, fy) and principal point
00181 # (cx, cy).
00182 float64[9] K # 3x3 row-major matrix
00183
00184 # Rectification matrix (stereo cameras only)
00185 # A rotation matrix aligning the camera coordinate system to the ideal
00186 # stereo image plane so that epipolar lines in both stereo images are
00187 # parallel.
00188 float64[9] R # 3x3 row-major matrix
00189
00190 # Projection/camera matrix
00191 # [fx' 0 cx' Tx]
00192 # P = [ 0 fy' cy' Ty]
00193 # [ 0 0 1 0]
00194 # By convention, this matrix specifies the intrinsic (camera) matrix
00195 # of the processed (rectified) image. That is, the left 3x3 portion
00196 # is the normal camera intrinsic matrix for the rectified image.
00197 # It projects 3D points in the camera coordinate frame to 2D pixel
00198 # coordinates using the focal lengths (fx', fy') and principal point
00199 # (cx', cy') - these may differ from the values in K.
00200 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00201 # also have R = the identity and P[1:3,1:3] = K.
00202 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00203 # position of the optical center of the second camera in the first
00204 # camera's frame. We assume Tz = 0 so both cameras are in the same
00205 # stereo image plane. The first camera always has Tx = Ty = 0. For
00206 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00207 # Tx = -fx' * B, where B is the baseline between the cameras.
00208 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00209 # the rectified image is given by:
00210 # [u v w]' = P * [X Y Z 1]'
00211 # x = u / w
00212 # y = v / w
00213 # This holds for both images of a stereo pair.
00214 float64[12] P # 3x4 row-major matrix
00215
00216
00217 #######################################################################
00218 # Operational Parameters #
00219 #######################################################################
00220 # These define the image region actually captured by the camera #
00221 # driver. Although they affect the geometry of the output image, they #
00222 # may be changed freely without recalibrating the camera. #
00223 #######################################################################
00224
00225 # Binning refers here to any camera setting which combines rectangular
00226 # neighborhoods of pixels into larger "super-pixels." It reduces the
00227 # resolution of the output image to
00228 # (width / binning_x) x (height / binning_y).
00229 # The default values binning_x = binning_y = 0 is considered the same
00230 # as binning_x = binning_y = 1 (no subsampling).
00231 uint32 binning_x
00232 uint32 binning_y
00233
00234 # Region of interest (subwindow of full camera resolution), given in
00235 # full resolution (unbinned) image coordinates. A particular ROI
00236 # always denotes the same window of pixels on the camera sensor,
00237 # regardless of binning settings.
00238 # The default setting of roi (all values 0) is considered the same as
00239 # full resolution (roi.width = width, roi.height = height).
00240 RegionOfInterest roi
00241
00242 ================================================================================
00243 MSG: sensor_msgs/RegionOfInterest
00244 # This message is used to specify a region of interest within an image.
00245 #
00246 # When used to specify the ROI setting of the camera when the image was
00247 # taken, the height and width fields should either match the height and
00248 # width fields for the associated image; or height = width = 0
00249 # indicates that the full resolution image was captured.
00250
00251 uint32 x_offset # Leftmost pixel of the ROI
00252 # (0 if the ROI includes the left edge of the image)
00253 uint32 y_offset # Topmost pixel of the ROI
00254 # (0 if the ROI includes the top edge of the image)
00255 uint32 height # Height of ROI
00256 uint32 width # Width of ROI
00257
00258 # True if a distinct rectified ROI should be calculated from the "raw"
00259 # ROI in this message. Typically this should be False if the full image
00260 # is captured (ROI not used), and True if a subwindow is captured (ROI
00261 # used).
00262 bool do_rectify
00263
00264 ================================================================================
00265 MSG: sensor_msgs/PointCloud2
00266 # This message holds a collection of N-dimensional points, which may
00267 # contain additional information such as normals, intensity, etc. The
00268 # point data is stored as a binary blob, its layout described by the
00269 # contents of the "fields" array.
00270
00271 # The point cloud data may be organized 2d (image-like) or 1d
00272 # (unordered). Point clouds organized as 2d images may be produced by
00273 # camera depth sensors such as stereo or time-of-flight.
00274
00275 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00276 # points).
00277 Header header
00278
00279 # 2D structure of the point cloud. If the cloud is unordered, height is
00280 # 1 and width is the length of the point cloud.
00281 uint32 height
00282 uint32 width
00283
00284 # Describes the channels and their layout in the binary data blob.
00285 PointField[] fields
00286
00287 bool is_bigendian # Is this data bigendian?
00288 uint32 point_step # Length of a point in bytes
00289 uint32 row_step # Length of a row in bytes
00290 uint8[] data # Actual point data, size is (row_step*height)
00291
00292 bool is_dense # True if there are no invalid points
00293
00294 ================================================================================
00295 MSG: sensor_msgs/PointField
00296 # This message holds the description of one point entry in the
00297 # PointCloud2 message format.
00298 uint8 INT8 = 1
00299 uint8 UINT8 = 2
00300 uint8 INT16 = 3
00301 uint8 UINT16 = 4
00302 uint8 INT32 = 5
00303 uint8 UINT32 = 6
00304 uint8 FLOAT32 = 7
00305 uint8 FLOAT64 = 8
00306
00307 string name # Name of field
00308 uint32 offset # Offset from start of point struct
00309 uint8 datatype # Datatype enumeration, see above
00310 uint32 count # How many elements in the field
00311
00312 ================================================================================
00313 MSG: stereo_msgs/DisparityImage
00314 # Separate header for compatibility with current TimeSynchronizer.
00315 # Likely to be removed in a later release, use image.header instead.
00316 Header header
00317
00318 # Floating point disparity image. The disparities are pre-adjusted for any
00319 # x-offset between the principal points of the two cameras (in the case
00320 # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)
00321 sensor_msgs/Image image
00322
00323 # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d.
00324 float32 f # Focal length, pixels
00325 float32 T # Baseline, world units
00326
00327 # Subwindow of (potentially) valid disparity values.
00328 sensor_msgs/RegionOfInterest valid_window
00329
00330 # The range of disparities searched.
00331 # In the disparity image, any disparity less than min_disparity is invalid.
00332 # The disparity search range defines the horopter, or 3D volume that the
00333 # stereo algorithm can "see". Points with Z outside of:
00334 # Z_min = fT / max_disparity
00335 # Z_max = fT / min_disparity
00336 # could not be found.
00337 float32 min_disparity
00338 float32 max_disparity
00339
00340 # Smallest allowed disparity increment. The smallest achievable depth range
00341 # resolution is delta_Z = (Z^2/fT)*delta_d.
00342 float32 delta_d
00343
00344 ================================================================================
00345 MSG: interactive_perception_msgs/ObjectSegmentationGuiActionResult
00346 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00347
00348 Header header
00349 actionlib_msgs/GoalStatus status
00350 ObjectSegmentationGuiResult result
00351
00352 ================================================================================
00353 MSG: actionlib_msgs/GoalStatus
00354 GoalID goal_id
00355 uint8 status
00356 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00357 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00358 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00359 # and has since completed its execution (Terminal State)
00360 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00361 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00362 # to some failure (Terminal State)
00363 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00364 # because the goal was unattainable or invalid (Terminal State)
00365 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00366 # and has not yet completed execution
00367 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00368 # but the action server has not yet confirmed that the goal is canceled
00369 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00370 # and was successfully cancelled (Terminal State)
00371 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00372 # sent over the wire by an action server
00373
00374 #Allow for the user to associate a string with GoalStatus for debugging
00375 string text
00376
00377
00378 ================================================================================
00379 MSG: interactive_perception_msgs/ObjectSegmentationGuiResult
00380 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00381 # The information for the plane that has been detected
00382 tabletop_object_detector/Table table
00383
00384 # The raw clusters detected in the scan
00385 sensor_msgs/PointCloud[] clusters
00386
00387 # Whether the detection has succeeded or failed
00388 int32 NO_CLOUD_RECEIVED = 1
00389 int32 NO_TABLE = 2
00390 int32 OTHER_ERROR = 3
00391 int32 SUCCESS = 4
00392 int32 result
00393
00394
00395 ================================================================================
00396 MSG: tabletop_object_detector/Table
00397 # Informs that a planar table has been detected at a given location
00398
00399 # The pose gives you the transform that take you to the coordinate system
00400 # of the table, with the origin somewhere in the table plane and the
00401 # z axis normal to the plane
00402 geometry_msgs/PoseStamped pose
00403
00404 # These values give you the observed extents of the table, along x and y,
00405 # in the table's own coordinate system (above)
00406 # there is no guarantee that the origin of the table coordinate system is
00407 # inside the boundary defined by these values.
00408 float32 x_min
00409 float32 x_max
00410 float32 y_min
00411 float32 y_max
00412
00413 # There is no guarantee that the table does NOT extend further than these
00414 # values; this is just as far as we've observed it.
00415
00416
00417 # Newer table definition as triangle mesh of convex hull (relative to pose)
00418 shape_msgs/Mesh convex_hull
00419
00420 ================================================================================
00421 MSG: geometry_msgs/PoseStamped
00422 # A Pose with reference coordinate frame and timestamp
00423 Header header
00424 Pose pose
00425
00426 ================================================================================
00427 MSG: geometry_msgs/Pose
00428 # A representation of pose in free space, composed of postion and orientation.
00429 Point position
00430 Quaternion orientation
00431
00432 ================================================================================
00433 MSG: geometry_msgs/Point
00434 # This contains the position of a point in free space
00435 float64 x
00436 float64 y
00437 float64 z
00438
00439 ================================================================================
00440 MSG: geometry_msgs/Quaternion
00441 # This represents an orientation in free space in quaternion form.
00442
00443 float64 x
00444 float64 y
00445 float64 z
00446 float64 w
00447
00448 ================================================================================
00449 MSG: shape_msgs/Mesh
00450 # Definition of a mesh
00451
00452 # list of triangles; the index values refer to positions in vertices[]
00453 MeshTriangle[] triangles
00454
00455 # the actual vertices that make up the mesh
00456 geometry_msgs/Point[] vertices
00457
00458 ================================================================================
00459 MSG: shape_msgs/MeshTriangle
00460 # Definition of a triangle's vertices
00461 uint32[3] vertex_indices
00462
00463 ================================================================================
00464 MSG: sensor_msgs/PointCloud
00465 # This message holds a collection of 3d points, plus optional additional
00466 # information about each point.
00467
00468 # Time of sensor data acquisition, coordinate frame ID.
00469 Header header
00470
00471 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00472 # in the frame given in the header.
00473 geometry_msgs/Point32[] points
00474
00475 # Each channel should have the same number of elements as points array,
00476 # and the data in each channel should correspond 1:1 with each point.
00477 # Channel names in common practice are listed in ChannelFloat32.msg.
00478 ChannelFloat32[] channels
00479
00480 ================================================================================
00481 MSG: geometry_msgs/Point32
00482 # This contains the position of a point in free space(with 32 bits of precision).
00483 # It is recommeded to use Point wherever possible instead of Point32.
00484 #
00485 # This recommendation is to promote interoperability.
00486 #
00487 # This message is designed to take up less space when sending
00488 # lots of points at once, as in the case of a PointCloud.
00489
00490 float32 x
00491 float32 y
00492 float32 z
00493 ================================================================================
00494 MSG: sensor_msgs/ChannelFloat32
00495 # This message is used by the PointCloud message to hold optional data
00496 # associated with each point in the cloud. The length of the values
00497 # array should be the same as the length of the points array in the
00498 # PointCloud, and each value should be associated with the corresponding
00499 # point.
00500
00501 # Channel names in existing practice include:
00502 # "u", "v" - row and column (respectively) in the left stereo image.
00503 # This is opposite to usual conventions but remains for
00504 # historical reasons. The newer PointCloud2 message has no
00505 # such problem.
00506 # "rgb" - For point clouds produced by color stereo cameras. uint8
00507 # (R,G,B) values packed into the least significant 24 bits,
00508 # in order.
00509 # "intensity" - laser or pixel intensity.
00510 # "distance"
00511
00512 # The channel name should give semantics of the channel (e.g.
00513 # "intensity" instead of "value").
00514 string name
00515
00516 # The values array should be 1-1 with the elements of the associated
00517 # PointCloud.
00518 float32[] values
00519
00520 ================================================================================
00521 MSG: interactive_perception_msgs/ObjectSegmentationGuiActionFeedback
00522 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00523
00524 Header header
00525 actionlib_msgs/GoalStatus status
00526 ObjectSegmentationGuiFeedback feedback
00527
00528 ================================================================================
00529 MSG: interactive_perception_msgs/ObjectSegmentationGuiFeedback
00530 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00531
00532
00533 """
00534 __slots__ = ['action_goal','action_result','action_feedback']
00535 _slot_types = ['interactive_perception_msgs/ObjectSegmentationGuiActionGoal','interactive_perception_msgs/ObjectSegmentationGuiActionResult','interactive_perception_msgs/ObjectSegmentationGuiActionFeedback']
00536
00537 def __init__(self, *args, **kwds):
00538 """
00539 Constructor. Any message fields that are implicitly/explicitly
00540 set to None will be assigned a default value. The recommend
00541 use is keyword arguments as this is more robust to future message
00542 changes. You cannot mix in-order arguments and keyword arguments.
00543
00544 The available fields are:
00545 action_goal,action_result,action_feedback
00546
00547 :param args: complete set of field values, in .msg order
00548 :param kwds: use keyword arguments corresponding to message field names
00549 to set specific fields.
00550 """
00551 if args or kwds:
00552 super(ObjectSegmentationGuiAction, self).__init__(*args, **kwds)
00553 #message fields cannot be None, assign default values for those that are
00554 if self.action_goal is None:
00555 self.action_goal = interactive_perception_msgs.msg.ObjectSegmentationGuiActionGoal()
00556 if self.action_result is None:
00557 self.action_result = interactive_perception_msgs.msg.ObjectSegmentationGuiActionResult()
00558 if self.action_feedback is None:
00559 self.action_feedback = interactive_perception_msgs.msg.ObjectSegmentationGuiActionFeedback()
00560 else:
00561 self.action_goal = interactive_perception_msgs.msg.ObjectSegmentationGuiActionGoal()
00562 self.action_result = interactive_perception_msgs.msg.ObjectSegmentationGuiActionResult()
00563 self.action_feedback = interactive_perception_msgs.msg.ObjectSegmentationGuiActionFeedback()
00564
00565 def _get_types(self):
00566 """
00567 internal API method
00568 """
00569 return self._slot_types
00570
00571 def serialize(self, buff):
00572 """
00573 serialize message into buffer
00574 :param buff: buffer, ``StringIO``
00575 """
00576 try:
00577 _x = self
00578 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00579 _x = self.action_goal.header.frame_id
00580 length = len(_x)
00581 if python3 or type(_x) == unicode:
00582 _x = _x.encode('utf-8')
00583 length = len(_x)
00584 buff.write(struct.pack('<I%ss'%length, length, _x))
00585 _x = self
00586 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00587 _x = self.action_goal.goal_id.id
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 _x = self
00594 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))
00595 _x = self.action_goal.goal.image.header.frame_id
00596 length = len(_x)
00597 if python3 or type(_x) == unicode:
00598 _x = _x.encode('utf-8')
00599 length = len(_x)
00600 buff.write(struct.pack('<I%ss'%length, length, _x))
00601 _x = self
00602 buff.write(_struct_2I.pack(_x.action_goal.goal.image.height, _x.action_goal.goal.image.width))
00603 _x = self.action_goal.goal.image.encoding
00604 length = len(_x)
00605 if python3 or type(_x) == unicode:
00606 _x = _x.encode('utf-8')
00607 length = len(_x)
00608 buff.write(struct.pack('<I%ss'%length, length, _x))
00609 _x = self
00610 buff.write(_struct_BI.pack(_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step))
00611 _x = self.action_goal.goal.image.data
00612 length = len(_x)
00613 # - if encoded as a list instead, serialize as bytes instead of string
00614 if type(_x) in [list, tuple]:
00615 buff.write(struct.pack('<I%sB'%length, length, *_x))
00616 else:
00617 buff.write(struct.pack('<I%ss'%length, length, _x))
00618 _x = self
00619 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))
00620 _x = self.action_goal.goal.camera_info.header.frame_id
00621 length = len(_x)
00622 if python3 or type(_x) == unicode:
00623 _x = _x.encode('utf-8')
00624 length = len(_x)
00625 buff.write(struct.pack('<I%ss'%length, length, _x))
00626 _x = self
00627 buff.write(_struct_2I.pack(_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width))
00628 _x = self.action_goal.goal.camera_info.distortion_model
00629 length = len(_x)
00630 if python3 or type(_x) == unicode:
00631 _x = _x.encode('utf-8')
00632 length = len(_x)
00633 buff.write(struct.pack('<I%ss'%length, length, _x))
00634 length = len(self.action_goal.goal.camera_info.D)
00635 buff.write(_struct_I.pack(length))
00636 pattern = '<%sd'%length
00637 buff.write(struct.pack(pattern, *self.action_goal.goal.camera_info.D))
00638 buff.write(_struct_9d.pack(*self.action_goal.goal.camera_info.K))
00639 buff.write(_struct_9d.pack(*self.action_goal.goal.camera_info.R))
00640 buff.write(_struct_12d.pack(*self.action_goal.goal.camera_info.P))
00641 _x = self
00642 buff.write(_struct_6IB3I.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, _x.action_goal.goal.wide_field.header.seq, _x.action_goal.goal.wide_field.header.stamp.secs, _x.action_goal.goal.wide_field.header.stamp.nsecs))
00643 _x = self.action_goal.goal.wide_field.header.frame_id
00644 length = len(_x)
00645 if python3 or type(_x) == unicode:
00646 _x = _x.encode('utf-8')
00647 length = len(_x)
00648 buff.write(struct.pack('<I%ss'%length, length, _x))
00649 _x = self
00650 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width))
00651 _x = self.action_goal.goal.wide_field.encoding
00652 length = len(_x)
00653 if python3 or type(_x) == unicode:
00654 _x = _x.encode('utf-8')
00655 length = len(_x)
00656 buff.write(struct.pack('<I%ss'%length, length, _x))
00657 _x = self
00658 buff.write(_struct_BI.pack(_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step))
00659 _x = self.action_goal.goal.wide_field.data
00660 length = len(_x)
00661 # - if encoded as a list instead, serialize as bytes instead of string
00662 if type(_x) in [list, tuple]:
00663 buff.write(struct.pack('<I%sB'%length, length, *_x))
00664 else:
00665 buff.write(struct.pack('<I%ss'%length, length, _x))
00666 _x = self
00667 buff.write(_struct_3I.pack(_x.action_goal.goal.wide_camera_info.header.seq, _x.action_goal.goal.wide_camera_info.header.stamp.secs, _x.action_goal.goal.wide_camera_info.header.stamp.nsecs))
00668 _x = self.action_goal.goal.wide_camera_info.header.frame_id
00669 length = len(_x)
00670 if python3 or type(_x) == unicode:
00671 _x = _x.encode('utf-8')
00672 length = len(_x)
00673 buff.write(struct.pack('<I%ss'%length, length, _x))
00674 _x = self
00675 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width))
00676 _x = self.action_goal.goal.wide_camera_info.distortion_model
00677 length = len(_x)
00678 if python3 or type(_x) == unicode:
00679 _x = _x.encode('utf-8')
00680 length = len(_x)
00681 buff.write(struct.pack('<I%ss'%length, length, _x))
00682 length = len(self.action_goal.goal.wide_camera_info.D)
00683 buff.write(_struct_I.pack(length))
00684 pattern = '<%sd'%length
00685 buff.write(struct.pack(pattern, *self.action_goal.goal.wide_camera_info.D))
00686 buff.write(_struct_9d.pack(*self.action_goal.goal.wide_camera_info.K))
00687 buff.write(_struct_9d.pack(*self.action_goal.goal.wide_camera_info.R))
00688 buff.write(_struct_12d.pack(*self.action_goal.goal.wide_camera_info.P))
00689 _x = self
00690 buff.write(_struct_6IB3I.pack(_x.action_goal.goal.wide_camera_info.binning_x, _x.action_goal.goal.wide_camera_info.binning_y, _x.action_goal.goal.wide_camera_info.roi.x_offset, _x.action_goal.goal.wide_camera_info.roi.y_offset, _x.action_goal.goal.wide_camera_info.roi.height, _x.action_goal.goal.wide_camera_info.roi.width, _x.action_goal.goal.wide_camera_info.roi.do_rectify, _x.action_goal.goal.point_cloud.header.seq, _x.action_goal.goal.point_cloud.header.stamp.secs, _x.action_goal.goal.point_cloud.header.stamp.nsecs))
00691 _x = self.action_goal.goal.point_cloud.header.frame_id
00692 length = len(_x)
00693 if python3 or type(_x) == unicode:
00694 _x = _x.encode('utf-8')
00695 length = len(_x)
00696 buff.write(struct.pack('<I%ss'%length, length, _x))
00697 _x = self
00698 buff.write(_struct_2I.pack(_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width))
00699 length = len(self.action_goal.goal.point_cloud.fields)
00700 buff.write(_struct_I.pack(length))
00701 for val1 in self.action_goal.goal.point_cloud.fields:
00702 _x = val1.name
00703 length = len(_x)
00704 if python3 or type(_x) == unicode:
00705 _x = _x.encode('utf-8')
00706 length = len(_x)
00707 buff.write(struct.pack('<I%ss'%length, length, _x))
00708 _x = val1
00709 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00710 _x = self
00711 buff.write(_struct_B2I.pack(_x.action_goal.goal.point_cloud.is_bigendian, _x.action_goal.goal.point_cloud.point_step, _x.action_goal.goal.point_cloud.row_step))
00712 _x = self.action_goal.goal.point_cloud.data
00713 length = len(_x)
00714 # - if encoded as a list instead, serialize as bytes instead of string
00715 if type(_x) in [list, tuple]:
00716 buff.write(struct.pack('<I%sB'%length, length, *_x))
00717 else:
00718 buff.write(struct.pack('<I%ss'%length, length, _x))
00719 _x = self
00720 buff.write(_struct_B3I.pack(_x.action_goal.goal.point_cloud.is_dense, _x.action_goal.goal.disparity_image.header.seq, _x.action_goal.goal.disparity_image.header.stamp.secs, _x.action_goal.goal.disparity_image.header.stamp.nsecs))
00721 _x = self.action_goal.goal.disparity_image.header.frame_id
00722 length = len(_x)
00723 if python3 or type(_x) == unicode:
00724 _x = _x.encode('utf-8')
00725 length = len(_x)
00726 buff.write(struct.pack('<I%ss'%length, length, _x))
00727 _x = self
00728 buff.write(_struct_3I.pack(_x.action_goal.goal.disparity_image.image.header.seq, _x.action_goal.goal.disparity_image.image.header.stamp.secs, _x.action_goal.goal.disparity_image.image.header.stamp.nsecs))
00729 _x = self.action_goal.goal.disparity_image.image.header.frame_id
00730 length = len(_x)
00731 if python3 or type(_x) == unicode:
00732 _x = _x.encode('utf-8')
00733 length = len(_x)
00734 buff.write(struct.pack('<I%ss'%length, length, _x))
00735 _x = self
00736 buff.write(_struct_2I.pack(_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width))
00737 _x = self.action_goal.goal.disparity_image.image.encoding
00738 length = len(_x)
00739 if python3 or type(_x) == unicode:
00740 _x = _x.encode('utf-8')
00741 length = len(_x)
00742 buff.write(struct.pack('<I%ss'%length, length, _x))
00743 _x = self
00744 buff.write(_struct_BI.pack(_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step))
00745 _x = self.action_goal.goal.disparity_image.image.data
00746 length = len(_x)
00747 # - if encoded as a list instead, serialize as bytes instead of string
00748 if type(_x) in [list, tuple]:
00749 buff.write(struct.pack('<I%sB'%length, length, *_x))
00750 else:
00751 buff.write(struct.pack('<I%ss'%length, length, _x))
00752 _x = self
00753 buff.write(_struct_2f4IB3f3I.pack(_x.action_goal.goal.disparity_image.f, _x.action_goal.goal.disparity_image.T, _x.action_goal.goal.disparity_image.valid_window.x_offset, _x.action_goal.goal.disparity_image.valid_window.y_offset, _x.action_goal.goal.disparity_image.valid_window.height, _x.action_goal.goal.disparity_image.valid_window.width, _x.action_goal.goal.disparity_image.valid_window.do_rectify, _x.action_goal.goal.disparity_image.min_disparity, _x.action_goal.goal.disparity_image.max_disparity, _x.action_goal.goal.disparity_image.delta_d, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00754 _x = self.action_result.header.frame_id
00755 length = len(_x)
00756 if python3 or type(_x) == unicode:
00757 _x = _x.encode('utf-8')
00758 length = len(_x)
00759 buff.write(struct.pack('<I%ss'%length, length, _x))
00760 _x = self
00761 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00762 _x = self.action_result.status.goal_id.id
00763 length = len(_x)
00764 if python3 or type(_x) == unicode:
00765 _x = _x.encode('utf-8')
00766 length = len(_x)
00767 buff.write(struct.pack('<I%ss'%length, length, _x))
00768 buff.write(_struct_B.pack(self.action_result.status.status))
00769 _x = self.action_result.status.text
00770 length = len(_x)
00771 if python3 or type(_x) == unicode:
00772 _x = _x.encode('utf-8')
00773 length = len(_x)
00774 buff.write(struct.pack('<I%ss'%length, length, _x))
00775 _x = self
00776 buff.write(_struct_3I.pack(_x.action_result.result.table.pose.header.seq, _x.action_result.result.table.pose.header.stamp.secs, _x.action_result.result.table.pose.header.stamp.nsecs))
00777 _x = self.action_result.result.table.pose.header.frame_id
00778 length = len(_x)
00779 if python3 or type(_x) == unicode:
00780 _x = _x.encode('utf-8')
00781 length = len(_x)
00782 buff.write(struct.pack('<I%ss'%length, length, _x))
00783 _x = self
00784 buff.write(_struct_7d4f.pack(_x.action_result.result.table.pose.pose.position.x, _x.action_result.result.table.pose.pose.position.y, _x.action_result.result.table.pose.pose.position.z, _x.action_result.result.table.pose.pose.orientation.x, _x.action_result.result.table.pose.pose.orientation.y, _x.action_result.result.table.pose.pose.orientation.z, _x.action_result.result.table.pose.pose.orientation.w, _x.action_result.result.table.x_min, _x.action_result.result.table.x_max, _x.action_result.result.table.y_min, _x.action_result.result.table.y_max))
00785 length = len(self.action_result.result.table.convex_hull.triangles)
00786 buff.write(_struct_I.pack(length))
00787 for val1 in self.action_result.result.table.convex_hull.triangles:
00788 buff.write(_struct_3I.pack(*val1.vertex_indices))
00789 length = len(self.action_result.result.table.convex_hull.vertices)
00790 buff.write(_struct_I.pack(length))
00791 for val1 in self.action_result.result.table.convex_hull.vertices:
00792 _x = val1
00793 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00794 length = len(self.action_result.result.clusters)
00795 buff.write(_struct_I.pack(length))
00796 for val1 in self.action_result.result.clusters:
00797 _v1 = val1.header
00798 buff.write(_struct_I.pack(_v1.seq))
00799 _v2 = _v1.stamp
00800 _x = _v2
00801 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00802 _x = _v1.frame_id
00803 length = len(_x)
00804 if python3 or type(_x) == unicode:
00805 _x = _x.encode('utf-8')
00806 length = len(_x)
00807 buff.write(struct.pack('<I%ss'%length, length, _x))
00808 length = len(val1.points)
00809 buff.write(_struct_I.pack(length))
00810 for val2 in val1.points:
00811 _x = val2
00812 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00813 length = len(val1.channels)
00814 buff.write(_struct_I.pack(length))
00815 for val2 in val1.channels:
00816 _x = val2.name
00817 length = len(_x)
00818 if python3 or type(_x) == unicode:
00819 _x = _x.encode('utf-8')
00820 length = len(_x)
00821 buff.write(struct.pack('<I%ss'%length, length, _x))
00822 length = len(val2.values)
00823 buff.write(_struct_I.pack(length))
00824 pattern = '<%sf'%length
00825 buff.write(struct.pack(pattern, *val2.values))
00826 _x = self
00827 buff.write(_struct_i3I.pack(_x.action_result.result.result, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00828 _x = self.action_feedback.header.frame_id
00829 length = len(_x)
00830 if python3 or type(_x) == unicode:
00831 _x = _x.encode('utf-8')
00832 length = len(_x)
00833 buff.write(struct.pack('<I%ss'%length, length, _x))
00834 _x = self
00835 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00836 _x = self.action_feedback.status.goal_id.id
00837 length = len(_x)
00838 if python3 or type(_x) == unicode:
00839 _x = _x.encode('utf-8')
00840 length = len(_x)
00841 buff.write(struct.pack('<I%ss'%length, length, _x))
00842 buff.write(_struct_B.pack(self.action_feedback.status.status))
00843 _x = self.action_feedback.status.text
00844 length = len(_x)
00845 if python3 or type(_x) == unicode:
00846 _x = _x.encode('utf-8')
00847 length = len(_x)
00848 buff.write(struct.pack('<I%ss'%length, length, _x))
00849 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00850 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00851
00852 def deserialize(self, str):
00853 """
00854 unpack serialized message in str into this message instance
00855 :param str: byte array of serialized message, ``str``
00856 """
00857 try:
00858 if self.action_goal is None:
00859 self.action_goal = interactive_perception_msgs.msg.ObjectSegmentationGuiActionGoal()
00860 if self.action_result is None:
00861 self.action_result = interactive_perception_msgs.msg.ObjectSegmentationGuiActionResult()
00862 if self.action_feedback is None:
00863 self.action_feedback = interactive_perception_msgs.msg.ObjectSegmentationGuiActionFeedback()
00864 end = 0
00865 _x = self
00866 start = end
00867 end += 12
00868 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00869 start = end
00870 end += 4
00871 (length,) = _struct_I.unpack(str[start:end])
00872 start = end
00873 end += length
00874 if python3:
00875 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00876 else:
00877 self.action_goal.header.frame_id = str[start:end]
00878 _x = self
00879 start = end
00880 end += 8
00881 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00882 start = end
00883 end += 4
00884 (length,) = _struct_I.unpack(str[start:end])
00885 start = end
00886 end += length
00887 if python3:
00888 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00889 else:
00890 self.action_goal.goal_id.id = str[start:end]
00891 _x = self
00892 start = end
00893 end += 12
00894 (_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])
00895 start = end
00896 end += 4
00897 (length,) = _struct_I.unpack(str[start:end])
00898 start = end
00899 end += length
00900 if python3:
00901 self.action_goal.goal.image.header.frame_id = str[start:end].decode('utf-8')
00902 else:
00903 self.action_goal.goal.image.header.frame_id = str[start:end]
00904 _x = self
00905 start = end
00906 end += 8
00907 (_x.action_goal.goal.image.height, _x.action_goal.goal.image.width,) = _struct_2I.unpack(str[start:end])
00908 start = end
00909 end += 4
00910 (length,) = _struct_I.unpack(str[start:end])
00911 start = end
00912 end += length
00913 if python3:
00914 self.action_goal.goal.image.encoding = str[start:end].decode('utf-8')
00915 else:
00916 self.action_goal.goal.image.encoding = str[start:end]
00917 _x = self
00918 start = end
00919 end += 5
00920 (_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step,) = _struct_BI.unpack(str[start:end])
00921 start = end
00922 end += 4
00923 (length,) = _struct_I.unpack(str[start:end])
00924 start = end
00925 end += length
00926 self.action_goal.goal.image.data = str[start:end]
00927 _x = self
00928 start = end
00929 end += 12
00930 (_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])
00931 start = end
00932 end += 4
00933 (length,) = _struct_I.unpack(str[start:end])
00934 start = end
00935 end += length
00936 if python3:
00937 self.action_goal.goal.camera_info.header.frame_id = str[start:end].decode('utf-8')
00938 else:
00939 self.action_goal.goal.camera_info.header.frame_id = str[start:end]
00940 _x = self
00941 start = end
00942 end += 8
00943 (_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width,) = _struct_2I.unpack(str[start:end])
00944 start = end
00945 end += 4
00946 (length,) = _struct_I.unpack(str[start:end])
00947 start = end
00948 end += length
00949 if python3:
00950 self.action_goal.goal.camera_info.distortion_model = str[start:end].decode('utf-8')
00951 else:
00952 self.action_goal.goal.camera_info.distortion_model = str[start:end]
00953 start = end
00954 end += 4
00955 (length,) = _struct_I.unpack(str[start:end])
00956 pattern = '<%sd'%length
00957 start = end
00958 end += struct.calcsize(pattern)
00959 self.action_goal.goal.camera_info.D = struct.unpack(pattern, str[start:end])
00960 start = end
00961 end += 72
00962 self.action_goal.goal.camera_info.K = _struct_9d.unpack(str[start:end])
00963 start = end
00964 end += 72
00965 self.action_goal.goal.camera_info.R = _struct_9d.unpack(str[start:end])
00966 start = end
00967 end += 96
00968 self.action_goal.goal.camera_info.P = _struct_12d.unpack(str[start:end])
00969 _x = self
00970 start = end
00971 end += 37
00972 (_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, _x.action_goal.goal.wide_field.header.seq, _x.action_goal.goal.wide_field.header.stamp.secs, _x.action_goal.goal.wide_field.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00973 self.action_goal.goal.camera_info.roi.do_rectify = bool(self.action_goal.goal.camera_info.roi.do_rectify)
00974 start = end
00975 end += 4
00976 (length,) = _struct_I.unpack(str[start:end])
00977 start = end
00978 end += length
00979 if python3:
00980 self.action_goal.goal.wide_field.header.frame_id = str[start:end].decode('utf-8')
00981 else:
00982 self.action_goal.goal.wide_field.header.frame_id = str[start:end]
00983 _x = self
00984 start = end
00985 end += 8
00986 (_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width,) = _struct_2I.unpack(str[start:end])
00987 start = end
00988 end += 4
00989 (length,) = _struct_I.unpack(str[start:end])
00990 start = end
00991 end += length
00992 if python3:
00993 self.action_goal.goal.wide_field.encoding = str[start:end].decode('utf-8')
00994 else:
00995 self.action_goal.goal.wide_field.encoding = str[start:end]
00996 _x = self
00997 start = end
00998 end += 5
00999 (_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step,) = _struct_BI.unpack(str[start:end])
01000 start = end
01001 end += 4
01002 (length,) = _struct_I.unpack(str[start:end])
01003 start = end
01004 end += length
01005 self.action_goal.goal.wide_field.data = str[start:end]
01006 _x = self
01007 start = end
01008 end += 12
01009 (_x.action_goal.goal.wide_camera_info.header.seq, _x.action_goal.goal.wide_camera_info.header.stamp.secs, _x.action_goal.goal.wide_camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01010 start = end
01011 end += 4
01012 (length,) = _struct_I.unpack(str[start:end])
01013 start = end
01014 end += length
01015 if python3:
01016 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end].decode('utf-8')
01017 else:
01018 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end]
01019 _x = self
01020 start = end
01021 end += 8
01022 (_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width,) = _struct_2I.unpack(str[start:end])
01023 start = end
01024 end += 4
01025 (length,) = _struct_I.unpack(str[start:end])
01026 start = end
01027 end += length
01028 if python3:
01029 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end].decode('utf-8')
01030 else:
01031 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end]
01032 start = end
01033 end += 4
01034 (length,) = _struct_I.unpack(str[start:end])
01035 pattern = '<%sd'%length
01036 start = end
01037 end += struct.calcsize(pattern)
01038 self.action_goal.goal.wide_camera_info.D = struct.unpack(pattern, str[start:end])
01039 start = end
01040 end += 72
01041 self.action_goal.goal.wide_camera_info.K = _struct_9d.unpack(str[start:end])
01042 start = end
01043 end += 72
01044 self.action_goal.goal.wide_camera_info.R = _struct_9d.unpack(str[start:end])
01045 start = end
01046 end += 96
01047 self.action_goal.goal.wide_camera_info.P = _struct_12d.unpack(str[start:end])
01048 _x = self
01049 start = end
01050 end += 37
01051 (_x.action_goal.goal.wide_camera_info.binning_x, _x.action_goal.goal.wide_camera_info.binning_y, _x.action_goal.goal.wide_camera_info.roi.x_offset, _x.action_goal.goal.wide_camera_info.roi.y_offset, _x.action_goal.goal.wide_camera_info.roi.height, _x.action_goal.goal.wide_camera_info.roi.width, _x.action_goal.goal.wide_camera_info.roi.do_rectify, _x.action_goal.goal.point_cloud.header.seq, _x.action_goal.goal.point_cloud.header.stamp.secs, _x.action_goal.goal.point_cloud.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01052 self.action_goal.goal.wide_camera_info.roi.do_rectify = bool(self.action_goal.goal.wide_camera_info.roi.do_rectify)
01053 start = end
01054 end += 4
01055 (length,) = _struct_I.unpack(str[start:end])
01056 start = end
01057 end += length
01058 if python3:
01059 self.action_goal.goal.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01060 else:
01061 self.action_goal.goal.point_cloud.header.frame_id = str[start:end]
01062 _x = self
01063 start = end
01064 end += 8
01065 (_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01066 start = end
01067 end += 4
01068 (length,) = _struct_I.unpack(str[start:end])
01069 self.action_goal.goal.point_cloud.fields = []
01070 for i in range(0, length):
01071 val1 = sensor_msgs.msg.PointField()
01072 start = end
01073 end += 4
01074 (length,) = _struct_I.unpack(str[start:end])
01075 start = end
01076 end += length
01077 if python3:
01078 val1.name = str[start:end].decode('utf-8')
01079 else:
01080 val1.name = str[start:end]
01081 _x = val1
01082 start = end
01083 end += 9
01084 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01085 self.action_goal.goal.point_cloud.fields.append(val1)
01086 _x = self
01087 start = end
01088 end += 9
01089 (_x.action_goal.goal.point_cloud.is_bigendian, _x.action_goal.goal.point_cloud.point_step, _x.action_goal.goal.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01090 self.action_goal.goal.point_cloud.is_bigendian = bool(self.action_goal.goal.point_cloud.is_bigendian)
01091 start = end
01092 end += 4
01093 (length,) = _struct_I.unpack(str[start:end])
01094 start = end
01095 end += length
01096 self.action_goal.goal.point_cloud.data = str[start:end]
01097 _x = self
01098 start = end
01099 end += 13
01100 (_x.action_goal.goal.point_cloud.is_dense, _x.action_goal.goal.disparity_image.header.seq, _x.action_goal.goal.disparity_image.header.stamp.secs, _x.action_goal.goal.disparity_image.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01101 self.action_goal.goal.point_cloud.is_dense = bool(self.action_goal.goal.point_cloud.is_dense)
01102 start = end
01103 end += 4
01104 (length,) = _struct_I.unpack(str[start:end])
01105 start = end
01106 end += length
01107 if python3:
01108 self.action_goal.goal.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01109 else:
01110 self.action_goal.goal.disparity_image.header.frame_id = str[start:end]
01111 _x = self
01112 start = end
01113 end += 12
01114 (_x.action_goal.goal.disparity_image.image.header.seq, _x.action_goal.goal.disparity_image.image.header.stamp.secs, _x.action_goal.goal.disparity_image.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01115 start = end
01116 end += 4
01117 (length,) = _struct_I.unpack(str[start:end])
01118 start = end
01119 end += length
01120 if python3:
01121 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end].decode('utf-8')
01122 else:
01123 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end]
01124 _x = self
01125 start = end
01126 end += 8
01127 (_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width,) = _struct_2I.unpack(str[start:end])
01128 start = end
01129 end += 4
01130 (length,) = _struct_I.unpack(str[start:end])
01131 start = end
01132 end += length
01133 if python3:
01134 self.action_goal.goal.disparity_image.image.encoding = str[start:end].decode('utf-8')
01135 else:
01136 self.action_goal.goal.disparity_image.image.encoding = str[start:end]
01137 _x = self
01138 start = end
01139 end += 5
01140 (_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step,) = _struct_BI.unpack(str[start:end])
01141 start = end
01142 end += 4
01143 (length,) = _struct_I.unpack(str[start:end])
01144 start = end
01145 end += length
01146 self.action_goal.goal.disparity_image.image.data = str[start:end]
01147 _x = self
01148 start = end
01149 end += 49
01150 (_x.action_goal.goal.disparity_image.f, _x.action_goal.goal.disparity_image.T, _x.action_goal.goal.disparity_image.valid_window.x_offset, _x.action_goal.goal.disparity_image.valid_window.y_offset, _x.action_goal.goal.disparity_image.valid_window.height, _x.action_goal.goal.disparity_image.valid_window.width, _x.action_goal.goal.disparity_image.valid_window.do_rectify, _x.action_goal.goal.disparity_image.min_disparity, _x.action_goal.goal.disparity_image.max_disparity, _x.action_goal.goal.disparity_image.delta_d, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_2f4IB3f3I.unpack(str[start:end])
01151 self.action_goal.goal.disparity_image.valid_window.do_rectify = bool(self.action_goal.goal.disparity_image.valid_window.do_rectify)
01152 start = end
01153 end += 4
01154 (length,) = _struct_I.unpack(str[start:end])
01155 start = end
01156 end += length
01157 if python3:
01158 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01159 else:
01160 self.action_result.header.frame_id = str[start:end]
01161 _x = self
01162 start = end
01163 end += 8
01164 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01165 start = end
01166 end += 4
01167 (length,) = _struct_I.unpack(str[start:end])
01168 start = end
01169 end += length
01170 if python3:
01171 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01172 else:
01173 self.action_result.status.goal_id.id = str[start:end]
01174 start = end
01175 end += 1
01176 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01177 start = end
01178 end += 4
01179 (length,) = _struct_I.unpack(str[start:end])
01180 start = end
01181 end += length
01182 if python3:
01183 self.action_result.status.text = str[start:end].decode('utf-8')
01184 else:
01185 self.action_result.status.text = str[start:end]
01186 _x = self
01187 start = end
01188 end += 12
01189 (_x.action_result.result.table.pose.header.seq, _x.action_result.result.table.pose.header.stamp.secs, _x.action_result.result.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01190 start = end
01191 end += 4
01192 (length,) = _struct_I.unpack(str[start:end])
01193 start = end
01194 end += length
01195 if python3:
01196 self.action_result.result.table.pose.header.frame_id = str[start:end].decode('utf-8')
01197 else:
01198 self.action_result.result.table.pose.header.frame_id = str[start:end]
01199 _x = self
01200 start = end
01201 end += 72
01202 (_x.action_result.result.table.pose.pose.position.x, _x.action_result.result.table.pose.pose.position.y, _x.action_result.result.table.pose.pose.position.z, _x.action_result.result.table.pose.pose.orientation.x, _x.action_result.result.table.pose.pose.orientation.y, _x.action_result.result.table.pose.pose.orientation.z, _x.action_result.result.table.pose.pose.orientation.w, _x.action_result.result.table.x_min, _x.action_result.result.table.x_max, _x.action_result.result.table.y_min, _x.action_result.result.table.y_max,) = _struct_7d4f.unpack(str[start:end])
01203 start = end
01204 end += 4
01205 (length,) = _struct_I.unpack(str[start:end])
01206 self.action_result.result.table.convex_hull.triangles = []
01207 for i in range(0, length):
01208 val1 = shape_msgs.msg.MeshTriangle()
01209 start = end
01210 end += 12
01211 val1.vertex_indices = _struct_3I.unpack(str[start:end])
01212 self.action_result.result.table.convex_hull.triangles.append(val1)
01213 start = end
01214 end += 4
01215 (length,) = _struct_I.unpack(str[start:end])
01216 self.action_result.result.table.convex_hull.vertices = []
01217 for i in range(0, length):
01218 val1 = geometry_msgs.msg.Point()
01219 _x = val1
01220 start = end
01221 end += 24
01222 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01223 self.action_result.result.table.convex_hull.vertices.append(val1)
01224 start = end
01225 end += 4
01226 (length,) = _struct_I.unpack(str[start:end])
01227 self.action_result.result.clusters = []
01228 for i in range(0, length):
01229 val1 = sensor_msgs.msg.PointCloud()
01230 _v3 = val1.header
01231 start = end
01232 end += 4
01233 (_v3.seq,) = _struct_I.unpack(str[start:end])
01234 _v4 = _v3.stamp
01235 _x = _v4
01236 start = end
01237 end += 8
01238 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01239 start = end
01240 end += 4
01241 (length,) = _struct_I.unpack(str[start:end])
01242 start = end
01243 end += length
01244 if python3:
01245 _v3.frame_id = str[start:end].decode('utf-8')
01246 else:
01247 _v3.frame_id = str[start:end]
01248 start = end
01249 end += 4
01250 (length,) = _struct_I.unpack(str[start:end])
01251 val1.points = []
01252 for i in range(0, length):
01253 val2 = geometry_msgs.msg.Point32()
01254 _x = val2
01255 start = end
01256 end += 12
01257 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01258 val1.points.append(val2)
01259 start = end
01260 end += 4
01261 (length,) = _struct_I.unpack(str[start:end])
01262 val1.channels = []
01263 for i in range(0, length):
01264 val2 = sensor_msgs.msg.ChannelFloat32()
01265 start = end
01266 end += 4
01267 (length,) = _struct_I.unpack(str[start:end])
01268 start = end
01269 end += length
01270 if python3:
01271 val2.name = str[start:end].decode('utf-8')
01272 else:
01273 val2.name = str[start:end]
01274 start = end
01275 end += 4
01276 (length,) = _struct_I.unpack(str[start:end])
01277 pattern = '<%sf'%length
01278 start = end
01279 end += struct.calcsize(pattern)
01280 val2.values = struct.unpack(pattern, str[start:end])
01281 val1.channels.append(val2)
01282 self.action_result.result.clusters.append(val1)
01283 _x = self
01284 start = end
01285 end += 16
01286 (_x.action_result.result.result, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
01287 start = end
01288 end += 4
01289 (length,) = _struct_I.unpack(str[start:end])
01290 start = end
01291 end += length
01292 if python3:
01293 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01294 else:
01295 self.action_feedback.header.frame_id = str[start:end]
01296 _x = self
01297 start = end
01298 end += 8
01299 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01300 start = end
01301 end += 4
01302 (length,) = _struct_I.unpack(str[start:end])
01303 start = end
01304 end += length
01305 if python3:
01306 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01307 else:
01308 self.action_feedback.status.goal_id.id = str[start:end]
01309 start = end
01310 end += 1
01311 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01312 start = end
01313 end += 4
01314 (length,) = _struct_I.unpack(str[start:end])
01315 start = end
01316 end += length
01317 if python3:
01318 self.action_feedback.status.text = str[start:end].decode('utf-8')
01319 else:
01320 self.action_feedback.status.text = str[start:end]
01321 return self
01322 except struct.error as e:
01323 raise genpy.DeserializationError(e) #most likely buffer underfill
01324
01325
01326 def serialize_numpy(self, buff, numpy):
01327 """
01328 serialize message with numpy array types into buffer
01329 :param buff: buffer, ``StringIO``
01330 :param numpy: numpy python module
01331 """
01332 try:
01333 _x = self
01334 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
01335 _x = self.action_goal.header.frame_id
01336 length = len(_x)
01337 if python3 or type(_x) == unicode:
01338 _x = _x.encode('utf-8')
01339 length = len(_x)
01340 buff.write(struct.pack('<I%ss'%length, length, _x))
01341 _x = self
01342 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
01343 _x = self.action_goal.goal_id.id
01344 length = len(_x)
01345 if python3 or type(_x) == unicode:
01346 _x = _x.encode('utf-8')
01347 length = len(_x)
01348 buff.write(struct.pack('<I%ss'%length, length, _x))
01349 _x = self
01350 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))
01351 _x = self.action_goal.goal.image.header.frame_id
01352 length = len(_x)
01353 if python3 or type(_x) == unicode:
01354 _x = _x.encode('utf-8')
01355 length = len(_x)
01356 buff.write(struct.pack('<I%ss'%length, length, _x))
01357 _x = self
01358 buff.write(_struct_2I.pack(_x.action_goal.goal.image.height, _x.action_goal.goal.image.width))
01359 _x = self.action_goal.goal.image.encoding
01360 length = len(_x)
01361 if python3 or type(_x) == unicode:
01362 _x = _x.encode('utf-8')
01363 length = len(_x)
01364 buff.write(struct.pack('<I%ss'%length, length, _x))
01365 _x = self
01366 buff.write(_struct_BI.pack(_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step))
01367 _x = self.action_goal.goal.image.data
01368 length = len(_x)
01369 # - if encoded as a list instead, serialize as bytes instead of string
01370 if type(_x) in [list, tuple]:
01371 buff.write(struct.pack('<I%sB'%length, length, *_x))
01372 else:
01373 buff.write(struct.pack('<I%ss'%length, length, _x))
01374 _x = self
01375 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))
01376 _x = self.action_goal.goal.camera_info.header.frame_id
01377 length = len(_x)
01378 if python3 or type(_x) == unicode:
01379 _x = _x.encode('utf-8')
01380 length = len(_x)
01381 buff.write(struct.pack('<I%ss'%length, length, _x))
01382 _x = self
01383 buff.write(_struct_2I.pack(_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width))
01384 _x = self.action_goal.goal.camera_info.distortion_model
01385 length = len(_x)
01386 if python3 or type(_x) == unicode:
01387 _x = _x.encode('utf-8')
01388 length = len(_x)
01389 buff.write(struct.pack('<I%ss'%length, length, _x))
01390 length = len(self.action_goal.goal.camera_info.D)
01391 buff.write(_struct_I.pack(length))
01392 pattern = '<%sd'%length
01393 buff.write(self.action_goal.goal.camera_info.D.tostring())
01394 buff.write(self.action_goal.goal.camera_info.K.tostring())
01395 buff.write(self.action_goal.goal.camera_info.R.tostring())
01396 buff.write(self.action_goal.goal.camera_info.P.tostring())
01397 _x = self
01398 buff.write(_struct_6IB3I.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, _x.action_goal.goal.wide_field.header.seq, _x.action_goal.goal.wide_field.header.stamp.secs, _x.action_goal.goal.wide_field.header.stamp.nsecs))
01399 _x = self.action_goal.goal.wide_field.header.frame_id
01400 length = len(_x)
01401 if python3 or type(_x) == unicode:
01402 _x = _x.encode('utf-8')
01403 length = len(_x)
01404 buff.write(struct.pack('<I%ss'%length, length, _x))
01405 _x = self
01406 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width))
01407 _x = self.action_goal.goal.wide_field.encoding
01408 length = len(_x)
01409 if python3 or type(_x) == unicode:
01410 _x = _x.encode('utf-8')
01411 length = len(_x)
01412 buff.write(struct.pack('<I%ss'%length, length, _x))
01413 _x = self
01414 buff.write(_struct_BI.pack(_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step))
01415 _x = self.action_goal.goal.wide_field.data
01416 length = len(_x)
01417 # - if encoded as a list instead, serialize as bytes instead of string
01418 if type(_x) in [list, tuple]:
01419 buff.write(struct.pack('<I%sB'%length, length, *_x))
01420 else:
01421 buff.write(struct.pack('<I%ss'%length, length, _x))
01422 _x = self
01423 buff.write(_struct_3I.pack(_x.action_goal.goal.wide_camera_info.header.seq, _x.action_goal.goal.wide_camera_info.header.stamp.secs, _x.action_goal.goal.wide_camera_info.header.stamp.nsecs))
01424 _x = self.action_goal.goal.wide_camera_info.header.frame_id
01425 length = len(_x)
01426 if python3 or type(_x) == unicode:
01427 _x = _x.encode('utf-8')
01428 length = len(_x)
01429 buff.write(struct.pack('<I%ss'%length, length, _x))
01430 _x = self
01431 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width))
01432 _x = self.action_goal.goal.wide_camera_info.distortion_model
01433 length = len(_x)
01434 if python3 or type(_x) == unicode:
01435 _x = _x.encode('utf-8')
01436 length = len(_x)
01437 buff.write(struct.pack('<I%ss'%length, length, _x))
01438 length = len(self.action_goal.goal.wide_camera_info.D)
01439 buff.write(_struct_I.pack(length))
01440 pattern = '<%sd'%length
01441 buff.write(self.action_goal.goal.wide_camera_info.D.tostring())
01442 buff.write(self.action_goal.goal.wide_camera_info.K.tostring())
01443 buff.write(self.action_goal.goal.wide_camera_info.R.tostring())
01444 buff.write(self.action_goal.goal.wide_camera_info.P.tostring())
01445 _x = self
01446 buff.write(_struct_6IB3I.pack(_x.action_goal.goal.wide_camera_info.binning_x, _x.action_goal.goal.wide_camera_info.binning_y, _x.action_goal.goal.wide_camera_info.roi.x_offset, _x.action_goal.goal.wide_camera_info.roi.y_offset, _x.action_goal.goal.wide_camera_info.roi.height, _x.action_goal.goal.wide_camera_info.roi.width, _x.action_goal.goal.wide_camera_info.roi.do_rectify, _x.action_goal.goal.point_cloud.header.seq, _x.action_goal.goal.point_cloud.header.stamp.secs, _x.action_goal.goal.point_cloud.header.stamp.nsecs))
01447 _x = self.action_goal.goal.point_cloud.header.frame_id
01448 length = len(_x)
01449 if python3 or type(_x) == unicode:
01450 _x = _x.encode('utf-8')
01451 length = len(_x)
01452 buff.write(struct.pack('<I%ss'%length, length, _x))
01453 _x = self
01454 buff.write(_struct_2I.pack(_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width))
01455 length = len(self.action_goal.goal.point_cloud.fields)
01456 buff.write(_struct_I.pack(length))
01457 for val1 in self.action_goal.goal.point_cloud.fields:
01458 _x = val1.name
01459 length = len(_x)
01460 if python3 or type(_x) == unicode:
01461 _x = _x.encode('utf-8')
01462 length = len(_x)
01463 buff.write(struct.pack('<I%ss'%length, length, _x))
01464 _x = val1
01465 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01466 _x = self
01467 buff.write(_struct_B2I.pack(_x.action_goal.goal.point_cloud.is_bigendian, _x.action_goal.goal.point_cloud.point_step, _x.action_goal.goal.point_cloud.row_step))
01468 _x = self.action_goal.goal.point_cloud.data
01469 length = len(_x)
01470 # - if encoded as a list instead, serialize as bytes instead of string
01471 if type(_x) in [list, tuple]:
01472 buff.write(struct.pack('<I%sB'%length, length, *_x))
01473 else:
01474 buff.write(struct.pack('<I%ss'%length, length, _x))
01475 _x = self
01476 buff.write(_struct_B3I.pack(_x.action_goal.goal.point_cloud.is_dense, _x.action_goal.goal.disparity_image.header.seq, _x.action_goal.goal.disparity_image.header.stamp.secs, _x.action_goal.goal.disparity_image.header.stamp.nsecs))
01477 _x = self.action_goal.goal.disparity_image.header.frame_id
01478 length = len(_x)
01479 if python3 or type(_x) == unicode:
01480 _x = _x.encode('utf-8')
01481 length = len(_x)
01482 buff.write(struct.pack('<I%ss'%length, length, _x))
01483 _x = self
01484 buff.write(_struct_3I.pack(_x.action_goal.goal.disparity_image.image.header.seq, _x.action_goal.goal.disparity_image.image.header.stamp.secs, _x.action_goal.goal.disparity_image.image.header.stamp.nsecs))
01485 _x = self.action_goal.goal.disparity_image.image.header.frame_id
01486 length = len(_x)
01487 if python3 or type(_x) == unicode:
01488 _x = _x.encode('utf-8')
01489 length = len(_x)
01490 buff.write(struct.pack('<I%ss'%length, length, _x))
01491 _x = self
01492 buff.write(_struct_2I.pack(_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width))
01493 _x = self.action_goal.goal.disparity_image.image.encoding
01494 length = len(_x)
01495 if python3 or type(_x) == unicode:
01496 _x = _x.encode('utf-8')
01497 length = len(_x)
01498 buff.write(struct.pack('<I%ss'%length, length, _x))
01499 _x = self
01500 buff.write(_struct_BI.pack(_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step))
01501 _x = self.action_goal.goal.disparity_image.image.data
01502 length = len(_x)
01503 # - if encoded as a list instead, serialize as bytes instead of string
01504 if type(_x) in [list, tuple]:
01505 buff.write(struct.pack('<I%sB'%length, length, *_x))
01506 else:
01507 buff.write(struct.pack('<I%ss'%length, length, _x))
01508 _x = self
01509 buff.write(_struct_2f4IB3f3I.pack(_x.action_goal.goal.disparity_image.f, _x.action_goal.goal.disparity_image.T, _x.action_goal.goal.disparity_image.valid_window.x_offset, _x.action_goal.goal.disparity_image.valid_window.y_offset, _x.action_goal.goal.disparity_image.valid_window.height, _x.action_goal.goal.disparity_image.valid_window.width, _x.action_goal.goal.disparity_image.valid_window.do_rectify, _x.action_goal.goal.disparity_image.min_disparity, _x.action_goal.goal.disparity_image.max_disparity, _x.action_goal.goal.disparity_image.delta_d, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
01510 _x = self.action_result.header.frame_id
01511 length = len(_x)
01512 if python3 or type(_x) == unicode:
01513 _x = _x.encode('utf-8')
01514 length = len(_x)
01515 buff.write(struct.pack('<I%ss'%length, length, _x))
01516 _x = self
01517 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
01518 _x = self.action_result.status.goal_id.id
01519 length = len(_x)
01520 if python3 or type(_x) == unicode:
01521 _x = _x.encode('utf-8')
01522 length = len(_x)
01523 buff.write(struct.pack('<I%ss'%length, length, _x))
01524 buff.write(_struct_B.pack(self.action_result.status.status))
01525 _x = self.action_result.status.text
01526 length = len(_x)
01527 if python3 or type(_x) == unicode:
01528 _x = _x.encode('utf-8')
01529 length = len(_x)
01530 buff.write(struct.pack('<I%ss'%length, length, _x))
01531 _x = self
01532 buff.write(_struct_3I.pack(_x.action_result.result.table.pose.header.seq, _x.action_result.result.table.pose.header.stamp.secs, _x.action_result.result.table.pose.header.stamp.nsecs))
01533 _x = self.action_result.result.table.pose.header.frame_id
01534 length = len(_x)
01535 if python3 or type(_x) == unicode:
01536 _x = _x.encode('utf-8')
01537 length = len(_x)
01538 buff.write(struct.pack('<I%ss'%length, length, _x))
01539 _x = self
01540 buff.write(_struct_7d4f.pack(_x.action_result.result.table.pose.pose.position.x, _x.action_result.result.table.pose.pose.position.y, _x.action_result.result.table.pose.pose.position.z, _x.action_result.result.table.pose.pose.orientation.x, _x.action_result.result.table.pose.pose.orientation.y, _x.action_result.result.table.pose.pose.orientation.z, _x.action_result.result.table.pose.pose.orientation.w, _x.action_result.result.table.x_min, _x.action_result.result.table.x_max, _x.action_result.result.table.y_min, _x.action_result.result.table.y_max))
01541 length = len(self.action_result.result.table.convex_hull.triangles)
01542 buff.write(_struct_I.pack(length))
01543 for val1 in self.action_result.result.table.convex_hull.triangles:
01544 buff.write(val1.vertex_indices.tostring())
01545 length = len(self.action_result.result.table.convex_hull.vertices)
01546 buff.write(_struct_I.pack(length))
01547 for val1 in self.action_result.result.table.convex_hull.vertices:
01548 _x = val1
01549 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01550 length = len(self.action_result.result.clusters)
01551 buff.write(_struct_I.pack(length))
01552 for val1 in self.action_result.result.clusters:
01553 _v5 = val1.header
01554 buff.write(_struct_I.pack(_v5.seq))
01555 _v6 = _v5.stamp
01556 _x = _v6
01557 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01558 _x = _v5.frame_id
01559 length = len(_x)
01560 if python3 or type(_x) == unicode:
01561 _x = _x.encode('utf-8')
01562 length = len(_x)
01563 buff.write(struct.pack('<I%ss'%length, length, _x))
01564 length = len(val1.points)
01565 buff.write(_struct_I.pack(length))
01566 for val2 in val1.points:
01567 _x = val2
01568 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01569 length = len(val1.channels)
01570 buff.write(_struct_I.pack(length))
01571 for val2 in val1.channels:
01572 _x = val2.name
01573 length = len(_x)
01574 if python3 or type(_x) == unicode:
01575 _x = _x.encode('utf-8')
01576 length = len(_x)
01577 buff.write(struct.pack('<I%ss'%length, length, _x))
01578 length = len(val2.values)
01579 buff.write(_struct_I.pack(length))
01580 pattern = '<%sf'%length
01581 buff.write(val2.values.tostring())
01582 _x = self
01583 buff.write(_struct_i3I.pack(_x.action_result.result.result, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
01584 _x = self.action_feedback.header.frame_id
01585 length = len(_x)
01586 if python3 or type(_x) == unicode:
01587 _x = _x.encode('utf-8')
01588 length = len(_x)
01589 buff.write(struct.pack('<I%ss'%length, length, _x))
01590 _x = self
01591 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
01592 _x = self.action_feedback.status.goal_id.id
01593 length = len(_x)
01594 if python3 or type(_x) == unicode:
01595 _x = _x.encode('utf-8')
01596 length = len(_x)
01597 buff.write(struct.pack('<I%ss'%length, length, _x))
01598 buff.write(_struct_B.pack(self.action_feedback.status.status))
01599 _x = self.action_feedback.status.text
01600 length = len(_x)
01601 if python3 or type(_x) == unicode:
01602 _x = _x.encode('utf-8')
01603 length = len(_x)
01604 buff.write(struct.pack('<I%ss'%length, length, _x))
01605 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
01606 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
01607
01608 def deserialize_numpy(self, str, numpy):
01609 """
01610 unpack serialized message in str into this message instance using numpy for array types
01611 :param str: byte array of serialized message, ``str``
01612 :param numpy: numpy python module
01613 """
01614 try:
01615 if self.action_goal is None:
01616 self.action_goal = interactive_perception_msgs.msg.ObjectSegmentationGuiActionGoal()
01617 if self.action_result is None:
01618 self.action_result = interactive_perception_msgs.msg.ObjectSegmentationGuiActionResult()
01619 if self.action_feedback is None:
01620 self.action_feedback = interactive_perception_msgs.msg.ObjectSegmentationGuiActionFeedback()
01621 end = 0
01622 _x = self
01623 start = end
01624 end += 12
01625 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01626 start = end
01627 end += 4
01628 (length,) = _struct_I.unpack(str[start:end])
01629 start = end
01630 end += length
01631 if python3:
01632 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
01633 else:
01634 self.action_goal.header.frame_id = str[start:end]
01635 _x = self
01636 start = end
01637 end += 8
01638 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01639 start = end
01640 end += 4
01641 (length,) = _struct_I.unpack(str[start:end])
01642 start = end
01643 end += length
01644 if python3:
01645 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
01646 else:
01647 self.action_goal.goal_id.id = str[start:end]
01648 _x = self
01649 start = end
01650 end += 12
01651 (_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])
01652 start = end
01653 end += 4
01654 (length,) = _struct_I.unpack(str[start:end])
01655 start = end
01656 end += length
01657 if python3:
01658 self.action_goal.goal.image.header.frame_id = str[start:end].decode('utf-8')
01659 else:
01660 self.action_goal.goal.image.header.frame_id = str[start:end]
01661 _x = self
01662 start = end
01663 end += 8
01664 (_x.action_goal.goal.image.height, _x.action_goal.goal.image.width,) = _struct_2I.unpack(str[start:end])
01665 start = end
01666 end += 4
01667 (length,) = _struct_I.unpack(str[start:end])
01668 start = end
01669 end += length
01670 if python3:
01671 self.action_goal.goal.image.encoding = str[start:end].decode('utf-8')
01672 else:
01673 self.action_goal.goal.image.encoding = str[start:end]
01674 _x = self
01675 start = end
01676 end += 5
01677 (_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step,) = _struct_BI.unpack(str[start:end])
01678 start = end
01679 end += 4
01680 (length,) = _struct_I.unpack(str[start:end])
01681 start = end
01682 end += length
01683 self.action_goal.goal.image.data = str[start:end]
01684 _x = self
01685 start = end
01686 end += 12
01687 (_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])
01688 start = end
01689 end += 4
01690 (length,) = _struct_I.unpack(str[start:end])
01691 start = end
01692 end += length
01693 if python3:
01694 self.action_goal.goal.camera_info.header.frame_id = str[start:end].decode('utf-8')
01695 else:
01696 self.action_goal.goal.camera_info.header.frame_id = str[start:end]
01697 _x = self
01698 start = end
01699 end += 8
01700 (_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width,) = _struct_2I.unpack(str[start:end])
01701 start = end
01702 end += 4
01703 (length,) = _struct_I.unpack(str[start:end])
01704 start = end
01705 end += length
01706 if python3:
01707 self.action_goal.goal.camera_info.distortion_model = str[start:end].decode('utf-8')
01708 else:
01709 self.action_goal.goal.camera_info.distortion_model = str[start:end]
01710 start = end
01711 end += 4
01712 (length,) = _struct_I.unpack(str[start:end])
01713 pattern = '<%sd'%length
01714 start = end
01715 end += struct.calcsize(pattern)
01716 self.action_goal.goal.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01717 start = end
01718 end += 72
01719 self.action_goal.goal.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01720 start = end
01721 end += 72
01722 self.action_goal.goal.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01723 start = end
01724 end += 96
01725 self.action_goal.goal.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01726 _x = self
01727 start = end
01728 end += 37
01729 (_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, _x.action_goal.goal.wide_field.header.seq, _x.action_goal.goal.wide_field.header.stamp.secs, _x.action_goal.goal.wide_field.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01730 self.action_goal.goal.camera_info.roi.do_rectify = bool(self.action_goal.goal.camera_info.roi.do_rectify)
01731 start = end
01732 end += 4
01733 (length,) = _struct_I.unpack(str[start:end])
01734 start = end
01735 end += length
01736 if python3:
01737 self.action_goal.goal.wide_field.header.frame_id = str[start:end].decode('utf-8')
01738 else:
01739 self.action_goal.goal.wide_field.header.frame_id = str[start:end]
01740 _x = self
01741 start = end
01742 end += 8
01743 (_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width,) = _struct_2I.unpack(str[start:end])
01744 start = end
01745 end += 4
01746 (length,) = _struct_I.unpack(str[start:end])
01747 start = end
01748 end += length
01749 if python3:
01750 self.action_goal.goal.wide_field.encoding = str[start:end].decode('utf-8')
01751 else:
01752 self.action_goal.goal.wide_field.encoding = str[start:end]
01753 _x = self
01754 start = end
01755 end += 5
01756 (_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step,) = _struct_BI.unpack(str[start:end])
01757 start = end
01758 end += 4
01759 (length,) = _struct_I.unpack(str[start:end])
01760 start = end
01761 end += length
01762 self.action_goal.goal.wide_field.data = str[start:end]
01763 _x = self
01764 start = end
01765 end += 12
01766 (_x.action_goal.goal.wide_camera_info.header.seq, _x.action_goal.goal.wide_camera_info.header.stamp.secs, _x.action_goal.goal.wide_camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01767 start = end
01768 end += 4
01769 (length,) = _struct_I.unpack(str[start:end])
01770 start = end
01771 end += length
01772 if python3:
01773 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end].decode('utf-8')
01774 else:
01775 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end]
01776 _x = self
01777 start = end
01778 end += 8
01779 (_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width,) = _struct_2I.unpack(str[start:end])
01780 start = end
01781 end += 4
01782 (length,) = _struct_I.unpack(str[start:end])
01783 start = end
01784 end += length
01785 if python3:
01786 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end].decode('utf-8')
01787 else:
01788 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end]
01789 start = end
01790 end += 4
01791 (length,) = _struct_I.unpack(str[start:end])
01792 pattern = '<%sd'%length
01793 start = end
01794 end += struct.calcsize(pattern)
01795 self.action_goal.goal.wide_camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01796 start = end
01797 end += 72
01798 self.action_goal.goal.wide_camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01799 start = end
01800 end += 72
01801 self.action_goal.goal.wide_camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01802 start = end
01803 end += 96
01804 self.action_goal.goal.wide_camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01805 _x = self
01806 start = end
01807 end += 37
01808 (_x.action_goal.goal.wide_camera_info.binning_x, _x.action_goal.goal.wide_camera_info.binning_y, _x.action_goal.goal.wide_camera_info.roi.x_offset, _x.action_goal.goal.wide_camera_info.roi.y_offset, _x.action_goal.goal.wide_camera_info.roi.height, _x.action_goal.goal.wide_camera_info.roi.width, _x.action_goal.goal.wide_camera_info.roi.do_rectify, _x.action_goal.goal.point_cloud.header.seq, _x.action_goal.goal.point_cloud.header.stamp.secs, _x.action_goal.goal.point_cloud.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01809 self.action_goal.goal.wide_camera_info.roi.do_rectify = bool(self.action_goal.goal.wide_camera_info.roi.do_rectify)
01810 start = end
01811 end += 4
01812 (length,) = _struct_I.unpack(str[start:end])
01813 start = end
01814 end += length
01815 if python3:
01816 self.action_goal.goal.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01817 else:
01818 self.action_goal.goal.point_cloud.header.frame_id = str[start:end]
01819 _x = self
01820 start = end
01821 end += 8
01822 (_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01823 start = end
01824 end += 4
01825 (length,) = _struct_I.unpack(str[start:end])
01826 self.action_goal.goal.point_cloud.fields = []
01827 for i in range(0, length):
01828 val1 = sensor_msgs.msg.PointField()
01829 start = end
01830 end += 4
01831 (length,) = _struct_I.unpack(str[start:end])
01832 start = end
01833 end += length
01834 if python3:
01835 val1.name = str[start:end].decode('utf-8')
01836 else:
01837 val1.name = str[start:end]
01838 _x = val1
01839 start = end
01840 end += 9
01841 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01842 self.action_goal.goal.point_cloud.fields.append(val1)
01843 _x = self
01844 start = end
01845 end += 9
01846 (_x.action_goal.goal.point_cloud.is_bigendian, _x.action_goal.goal.point_cloud.point_step, _x.action_goal.goal.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01847 self.action_goal.goal.point_cloud.is_bigendian = bool(self.action_goal.goal.point_cloud.is_bigendian)
01848 start = end
01849 end += 4
01850 (length,) = _struct_I.unpack(str[start:end])
01851 start = end
01852 end += length
01853 self.action_goal.goal.point_cloud.data = str[start:end]
01854 _x = self
01855 start = end
01856 end += 13
01857 (_x.action_goal.goal.point_cloud.is_dense, _x.action_goal.goal.disparity_image.header.seq, _x.action_goal.goal.disparity_image.header.stamp.secs, _x.action_goal.goal.disparity_image.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01858 self.action_goal.goal.point_cloud.is_dense = bool(self.action_goal.goal.point_cloud.is_dense)
01859 start = end
01860 end += 4
01861 (length,) = _struct_I.unpack(str[start:end])
01862 start = end
01863 end += length
01864 if python3:
01865 self.action_goal.goal.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01866 else:
01867 self.action_goal.goal.disparity_image.header.frame_id = str[start:end]
01868 _x = self
01869 start = end
01870 end += 12
01871 (_x.action_goal.goal.disparity_image.image.header.seq, _x.action_goal.goal.disparity_image.image.header.stamp.secs, _x.action_goal.goal.disparity_image.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01872 start = end
01873 end += 4
01874 (length,) = _struct_I.unpack(str[start:end])
01875 start = end
01876 end += length
01877 if python3:
01878 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end].decode('utf-8')
01879 else:
01880 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end]
01881 _x = self
01882 start = end
01883 end += 8
01884 (_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width,) = _struct_2I.unpack(str[start:end])
01885 start = end
01886 end += 4
01887 (length,) = _struct_I.unpack(str[start:end])
01888 start = end
01889 end += length
01890 if python3:
01891 self.action_goal.goal.disparity_image.image.encoding = str[start:end].decode('utf-8')
01892 else:
01893 self.action_goal.goal.disparity_image.image.encoding = str[start:end]
01894 _x = self
01895 start = end
01896 end += 5
01897 (_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step,) = _struct_BI.unpack(str[start:end])
01898 start = end
01899 end += 4
01900 (length,) = _struct_I.unpack(str[start:end])
01901 start = end
01902 end += length
01903 self.action_goal.goal.disparity_image.image.data = str[start:end]
01904 _x = self
01905 start = end
01906 end += 49
01907 (_x.action_goal.goal.disparity_image.f, _x.action_goal.goal.disparity_image.T, _x.action_goal.goal.disparity_image.valid_window.x_offset, _x.action_goal.goal.disparity_image.valid_window.y_offset, _x.action_goal.goal.disparity_image.valid_window.height, _x.action_goal.goal.disparity_image.valid_window.width, _x.action_goal.goal.disparity_image.valid_window.do_rectify, _x.action_goal.goal.disparity_image.min_disparity, _x.action_goal.goal.disparity_image.max_disparity, _x.action_goal.goal.disparity_image.delta_d, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_2f4IB3f3I.unpack(str[start:end])
01908 self.action_goal.goal.disparity_image.valid_window.do_rectify = bool(self.action_goal.goal.disparity_image.valid_window.do_rectify)
01909 start = end
01910 end += 4
01911 (length,) = _struct_I.unpack(str[start:end])
01912 start = end
01913 end += length
01914 if python3:
01915 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01916 else:
01917 self.action_result.header.frame_id = str[start:end]
01918 _x = self
01919 start = end
01920 end += 8
01921 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01922 start = end
01923 end += 4
01924 (length,) = _struct_I.unpack(str[start:end])
01925 start = end
01926 end += length
01927 if python3:
01928 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01929 else:
01930 self.action_result.status.goal_id.id = str[start:end]
01931 start = end
01932 end += 1
01933 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01934 start = end
01935 end += 4
01936 (length,) = _struct_I.unpack(str[start:end])
01937 start = end
01938 end += length
01939 if python3:
01940 self.action_result.status.text = str[start:end].decode('utf-8')
01941 else:
01942 self.action_result.status.text = str[start:end]
01943 _x = self
01944 start = end
01945 end += 12
01946 (_x.action_result.result.table.pose.header.seq, _x.action_result.result.table.pose.header.stamp.secs, _x.action_result.result.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01947 start = end
01948 end += 4
01949 (length,) = _struct_I.unpack(str[start:end])
01950 start = end
01951 end += length
01952 if python3:
01953 self.action_result.result.table.pose.header.frame_id = str[start:end].decode('utf-8')
01954 else:
01955 self.action_result.result.table.pose.header.frame_id = str[start:end]
01956 _x = self
01957 start = end
01958 end += 72
01959 (_x.action_result.result.table.pose.pose.position.x, _x.action_result.result.table.pose.pose.position.y, _x.action_result.result.table.pose.pose.position.z, _x.action_result.result.table.pose.pose.orientation.x, _x.action_result.result.table.pose.pose.orientation.y, _x.action_result.result.table.pose.pose.orientation.z, _x.action_result.result.table.pose.pose.orientation.w, _x.action_result.result.table.x_min, _x.action_result.result.table.x_max, _x.action_result.result.table.y_min, _x.action_result.result.table.y_max,) = _struct_7d4f.unpack(str[start:end])
01960 start = end
01961 end += 4
01962 (length,) = _struct_I.unpack(str[start:end])
01963 self.action_result.result.table.convex_hull.triangles = []
01964 for i in range(0, length):
01965 val1 = shape_msgs.msg.MeshTriangle()
01966 start = end
01967 end += 12
01968 val1.vertex_indices = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=3)
01969 self.action_result.result.table.convex_hull.triangles.append(val1)
01970 start = end
01971 end += 4
01972 (length,) = _struct_I.unpack(str[start:end])
01973 self.action_result.result.table.convex_hull.vertices = []
01974 for i in range(0, length):
01975 val1 = geometry_msgs.msg.Point()
01976 _x = val1
01977 start = end
01978 end += 24
01979 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01980 self.action_result.result.table.convex_hull.vertices.append(val1)
01981 start = end
01982 end += 4
01983 (length,) = _struct_I.unpack(str[start:end])
01984 self.action_result.result.clusters = []
01985 for i in range(0, length):
01986 val1 = sensor_msgs.msg.PointCloud()
01987 _v7 = val1.header
01988 start = end
01989 end += 4
01990 (_v7.seq,) = _struct_I.unpack(str[start:end])
01991 _v8 = _v7.stamp
01992 _x = _v8
01993 start = end
01994 end += 8
01995 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01996 start = end
01997 end += 4
01998 (length,) = _struct_I.unpack(str[start:end])
01999 start = end
02000 end += length
02001 if python3:
02002 _v7.frame_id = str[start:end].decode('utf-8')
02003 else:
02004 _v7.frame_id = str[start:end]
02005 start = end
02006 end += 4
02007 (length,) = _struct_I.unpack(str[start:end])
02008 val1.points = []
02009 for i in range(0, length):
02010 val2 = geometry_msgs.msg.Point32()
02011 _x = val2
02012 start = end
02013 end += 12
02014 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02015 val1.points.append(val2)
02016 start = end
02017 end += 4
02018 (length,) = _struct_I.unpack(str[start:end])
02019 val1.channels = []
02020 for i in range(0, length):
02021 val2 = sensor_msgs.msg.ChannelFloat32()
02022 start = end
02023 end += 4
02024 (length,) = _struct_I.unpack(str[start:end])
02025 start = end
02026 end += length
02027 if python3:
02028 val2.name = str[start:end].decode('utf-8')
02029 else:
02030 val2.name = str[start:end]
02031 start = end
02032 end += 4
02033 (length,) = _struct_I.unpack(str[start:end])
02034 pattern = '<%sf'%length
02035 start = end
02036 end += struct.calcsize(pattern)
02037 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
02038 val1.channels.append(val2)
02039 self.action_result.result.clusters.append(val1)
02040 _x = self
02041 start = end
02042 end += 16
02043 (_x.action_result.result.result, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
02044 start = end
02045 end += 4
02046 (length,) = _struct_I.unpack(str[start:end])
02047 start = end
02048 end += length
02049 if python3:
02050 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
02051 else:
02052 self.action_feedback.header.frame_id = str[start:end]
02053 _x = self
02054 start = end
02055 end += 8
02056 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02057 start = end
02058 end += 4
02059 (length,) = _struct_I.unpack(str[start:end])
02060 start = end
02061 end += length
02062 if python3:
02063 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
02064 else:
02065 self.action_feedback.status.goal_id.id = str[start:end]
02066 start = end
02067 end += 1
02068 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
02069 start = end
02070 end += 4
02071 (length,) = _struct_I.unpack(str[start:end])
02072 start = end
02073 end += length
02074 if python3:
02075 self.action_feedback.status.text = str[start:end].decode('utf-8')
02076 else:
02077 self.action_feedback.status.text = str[start:end]
02078 return self
02079 except struct.error as e:
02080 raise genpy.DeserializationError(e) #most likely buffer underfill
02081
02082 _struct_I = genpy.struct_I
02083 _struct_IBI = struct.Struct("<IBI")
02084 _struct_6IB3I = struct.Struct("<6IB3I")
02085 _struct_B = struct.Struct("<B")
02086 _struct_12d = struct.Struct("<12d")
02087 _struct_7d4f = struct.Struct("<7d4f")
02088 _struct_9d = struct.Struct("<9d")
02089 _struct_BI = struct.Struct("<BI")
02090 _struct_3f = struct.Struct("<3f")
02091 _struct_3I = struct.Struct("<3I")
02092 _struct_B3I = struct.Struct("<B3I")
02093 _struct_B2I = struct.Struct("<B2I")
02094 _struct_2f4IB3f3I = struct.Struct("<2f4IB3f3I")
02095 _struct_i3I = struct.Struct("<i3I")
02096 _struct_2I = struct.Struct("<2I")
02097 _struct_3d = struct.Struct("<3d")