00001 """autogenerated by genpy from object_segmentation_gui/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 arm_navigation_msgs.msg
00008 import tabletop_object_detector.msg
00009 import actionlib_msgs.msg
00010 import geometry_msgs.msg
00011 import stereo_msgs.msg
00012 import sensor_msgs.msg
00013 import genpy
00014 import object_segmentation_gui.msg
00015 import std_msgs.msg
00016
00017 class ObjectSegmentationGuiAction(genpy.Message):
00018 _md5sum = "ef7ff001f65c9b85b7778ccfa48cf741"
00019 _type = "object_segmentation_gui/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: object_segmentation_gui/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: object_segmentation_gui/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 src/image_encodings.cpp
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: object_segmentation_gui/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: object_segmentation_gui/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 arm_navigation_msgs/Shape 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: arm_navigation_msgs/Shape
00450 byte SPHERE=0
00451 byte BOX=1
00452 byte CYLINDER=2
00453 byte MESH=3
00454
00455 byte type
00456
00457
00458 #### define sphere, box, cylinder ####
00459 # the origin of each shape is considered at the shape's center
00460
00461 # for sphere
00462 # radius := dimensions[0]
00463
00464 # for cylinder
00465 # radius := dimensions[0]
00466 # length := dimensions[1]
00467 # the length is along the Z axis
00468
00469 # for box
00470 # size_x := dimensions[0]
00471 # size_y := dimensions[1]
00472 # size_z := dimensions[2]
00473 float64[] dimensions
00474
00475
00476 #### define mesh ####
00477
00478 # list of triangles; triangle k is defined by tre vertices located
00479 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00480 int32[] triangles
00481 geometry_msgs/Point[] vertices
00482
00483 ================================================================================
00484 MSG: sensor_msgs/PointCloud
00485 # This message holds a collection of 3d points, plus optional additional
00486 # information about each point.
00487
00488 # Time of sensor data acquisition, coordinate frame ID.
00489 Header header
00490
00491 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00492 # in the frame given in the header.
00493 geometry_msgs/Point32[] points
00494
00495 # Each channel should have the same number of elements as points array,
00496 # and the data in each channel should correspond 1:1 with each point.
00497 # Channel names in common practice are listed in ChannelFloat32.msg.
00498 ChannelFloat32[] channels
00499
00500 ================================================================================
00501 MSG: geometry_msgs/Point32
00502 # This contains the position of a point in free space(with 32 bits of precision).
00503 # It is recommeded to use Point wherever possible instead of Point32.
00504 #
00505 # This recommendation is to promote interoperability.
00506 #
00507 # This message is designed to take up less space when sending
00508 # lots of points at once, as in the case of a PointCloud.
00509
00510 float32 x
00511 float32 y
00512 float32 z
00513 ================================================================================
00514 MSG: sensor_msgs/ChannelFloat32
00515 # This message is used by the PointCloud message to hold optional data
00516 # associated with each point in the cloud. The length of the values
00517 # array should be the same as the length of the points array in the
00518 # PointCloud, and each value should be associated with the corresponding
00519 # point.
00520
00521 # Channel names in existing practice include:
00522 # "u", "v" - row and column (respectively) in the left stereo image.
00523 # This is opposite to usual conventions but remains for
00524 # historical reasons. The newer PointCloud2 message has no
00525 # such problem.
00526 # "rgb" - For point clouds produced by color stereo cameras. uint8
00527 # (R,G,B) values packed into the least significant 24 bits,
00528 # in order.
00529 # "intensity" - laser or pixel intensity.
00530 # "distance"
00531
00532 # The channel name should give semantics of the channel (e.g.
00533 # "intensity" instead of "value").
00534 string name
00535
00536 # The values array should be 1-1 with the elements of the associated
00537 # PointCloud.
00538 float32[] values
00539
00540 ================================================================================
00541 MSG: object_segmentation_gui/ObjectSegmentationGuiActionFeedback
00542 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00543
00544 Header header
00545 actionlib_msgs/GoalStatus status
00546 ObjectSegmentationGuiFeedback feedback
00547
00548 ================================================================================
00549 MSG: object_segmentation_gui/ObjectSegmentationGuiFeedback
00550 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00551
00552
00553 """
00554 __slots__ = ['action_goal','action_result','action_feedback']
00555 _slot_types = ['object_segmentation_gui/ObjectSegmentationGuiActionGoal','object_segmentation_gui/ObjectSegmentationGuiActionResult','object_segmentation_gui/ObjectSegmentationGuiActionFeedback']
00556
00557 def __init__(self, *args, **kwds):
00558 """
00559 Constructor. Any message fields that are implicitly/explicitly
00560 set to None will be assigned a default value. The recommend
00561 use is keyword arguments as this is more robust to future message
00562 changes. You cannot mix in-order arguments and keyword arguments.
00563
00564 The available fields are:
00565 action_goal,action_result,action_feedback
00566
00567 :param args: complete set of field values, in .msg order
00568 :param kwds: use keyword arguments corresponding to message field names
00569 to set specific fields.
00570 """
00571 if args or kwds:
00572 super(ObjectSegmentationGuiAction, self).__init__(*args, **kwds)
00573 #message fields cannot be None, assign default values for those that are
00574 if self.action_goal is None:
00575 self.action_goal = object_segmentation_gui.msg.ObjectSegmentationGuiActionGoal()
00576 if self.action_result is None:
00577 self.action_result = object_segmentation_gui.msg.ObjectSegmentationGuiActionResult()
00578 if self.action_feedback is None:
00579 self.action_feedback = object_segmentation_gui.msg.ObjectSegmentationGuiActionFeedback()
00580 else:
00581 self.action_goal = object_segmentation_gui.msg.ObjectSegmentationGuiActionGoal()
00582 self.action_result = object_segmentation_gui.msg.ObjectSegmentationGuiActionResult()
00583 self.action_feedback = object_segmentation_gui.msg.ObjectSegmentationGuiActionFeedback()
00584
00585 def _get_types(self):
00586 """
00587 internal API method
00588 """
00589 return self._slot_types
00590
00591 def serialize(self, buff):
00592 """
00593 serialize message into buffer
00594 :param buff: buffer, ``StringIO``
00595 """
00596 try:
00597 _x = self
00598 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00599 _x = self.action_goal.header.frame_id
00600 length = len(_x)
00601 if python3 or type(_x) == unicode:
00602 _x = _x.encode('utf-8')
00603 length = len(_x)
00604 buff.write(struct.pack('<I%ss'%length, length, _x))
00605 _x = self
00606 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00607 _x = self.action_goal.goal_id.id
00608 length = len(_x)
00609 if python3 or type(_x) == unicode:
00610 _x = _x.encode('utf-8')
00611 length = len(_x)
00612 buff.write(struct.pack('<I%ss'%length, length, _x))
00613 _x = self
00614 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))
00615 _x = self.action_goal.goal.image.header.frame_id
00616 length = len(_x)
00617 if python3 or type(_x) == unicode:
00618 _x = _x.encode('utf-8')
00619 length = len(_x)
00620 buff.write(struct.pack('<I%ss'%length, length, _x))
00621 _x = self
00622 buff.write(_struct_2I.pack(_x.action_goal.goal.image.height, _x.action_goal.goal.image.width))
00623 _x = self.action_goal.goal.image.encoding
00624 length = len(_x)
00625 if python3 or type(_x) == unicode:
00626 _x = _x.encode('utf-8')
00627 length = len(_x)
00628 buff.write(struct.pack('<I%ss'%length, length, _x))
00629 _x = self
00630 buff.write(_struct_BI.pack(_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step))
00631 _x = self.action_goal.goal.image.data
00632 length = len(_x)
00633 # - if encoded as a list instead, serialize as bytes instead of string
00634 if type(_x) in [list, tuple]:
00635 buff.write(struct.pack('<I%sB'%length, length, *_x))
00636 else:
00637 buff.write(struct.pack('<I%ss'%length, length, _x))
00638 _x = self
00639 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))
00640 _x = self.action_goal.goal.camera_info.header.frame_id
00641 length = len(_x)
00642 if python3 or type(_x) == unicode:
00643 _x = _x.encode('utf-8')
00644 length = len(_x)
00645 buff.write(struct.pack('<I%ss'%length, length, _x))
00646 _x = self
00647 buff.write(_struct_2I.pack(_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width))
00648 _x = self.action_goal.goal.camera_info.distortion_model
00649 length = len(_x)
00650 if python3 or type(_x) == unicode:
00651 _x = _x.encode('utf-8')
00652 length = len(_x)
00653 buff.write(struct.pack('<I%ss'%length, length, _x))
00654 length = len(self.action_goal.goal.camera_info.D)
00655 buff.write(_struct_I.pack(length))
00656 pattern = '<%sd'%length
00657 buff.write(struct.pack(pattern, *self.action_goal.goal.camera_info.D))
00658 buff.write(_struct_9d.pack(*self.action_goal.goal.camera_info.K))
00659 buff.write(_struct_9d.pack(*self.action_goal.goal.camera_info.R))
00660 buff.write(_struct_12d.pack(*self.action_goal.goal.camera_info.P))
00661 _x = self
00662 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))
00663 _x = self.action_goal.goal.wide_field.header.frame_id
00664 length = len(_x)
00665 if python3 or type(_x) == unicode:
00666 _x = _x.encode('utf-8')
00667 length = len(_x)
00668 buff.write(struct.pack('<I%ss'%length, length, _x))
00669 _x = self
00670 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width))
00671 _x = self.action_goal.goal.wide_field.encoding
00672 length = len(_x)
00673 if python3 or type(_x) == unicode:
00674 _x = _x.encode('utf-8')
00675 length = len(_x)
00676 buff.write(struct.pack('<I%ss'%length, length, _x))
00677 _x = self
00678 buff.write(_struct_BI.pack(_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step))
00679 _x = self.action_goal.goal.wide_field.data
00680 length = len(_x)
00681 # - if encoded as a list instead, serialize as bytes instead of string
00682 if type(_x) in [list, tuple]:
00683 buff.write(struct.pack('<I%sB'%length, length, *_x))
00684 else:
00685 buff.write(struct.pack('<I%ss'%length, length, _x))
00686 _x = self
00687 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))
00688 _x = self.action_goal.goal.wide_camera_info.header.frame_id
00689 length = len(_x)
00690 if python3 or type(_x) == unicode:
00691 _x = _x.encode('utf-8')
00692 length = len(_x)
00693 buff.write(struct.pack('<I%ss'%length, length, _x))
00694 _x = self
00695 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width))
00696 _x = self.action_goal.goal.wide_camera_info.distortion_model
00697 length = len(_x)
00698 if python3 or type(_x) == unicode:
00699 _x = _x.encode('utf-8')
00700 length = len(_x)
00701 buff.write(struct.pack('<I%ss'%length, length, _x))
00702 length = len(self.action_goal.goal.wide_camera_info.D)
00703 buff.write(_struct_I.pack(length))
00704 pattern = '<%sd'%length
00705 buff.write(struct.pack(pattern, *self.action_goal.goal.wide_camera_info.D))
00706 buff.write(_struct_9d.pack(*self.action_goal.goal.wide_camera_info.K))
00707 buff.write(_struct_9d.pack(*self.action_goal.goal.wide_camera_info.R))
00708 buff.write(_struct_12d.pack(*self.action_goal.goal.wide_camera_info.P))
00709 _x = self
00710 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))
00711 _x = self.action_goal.goal.point_cloud.header.frame_id
00712 length = len(_x)
00713 if python3 or type(_x) == unicode:
00714 _x = _x.encode('utf-8')
00715 length = len(_x)
00716 buff.write(struct.pack('<I%ss'%length, length, _x))
00717 _x = self
00718 buff.write(_struct_2I.pack(_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width))
00719 length = len(self.action_goal.goal.point_cloud.fields)
00720 buff.write(_struct_I.pack(length))
00721 for val1 in self.action_goal.goal.point_cloud.fields:
00722 _x = val1.name
00723 length = len(_x)
00724 if python3 or type(_x) == unicode:
00725 _x = _x.encode('utf-8')
00726 length = len(_x)
00727 buff.write(struct.pack('<I%ss'%length, length, _x))
00728 _x = val1
00729 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00730 _x = self
00731 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))
00732 _x = self.action_goal.goal.point_cloud.data
00733 length = len(_x)
00734 # - if encoded as a list instead, serialize as bytes instead of string
00735 if type(_x) in [list, tuple]:
00736 buff.write(struct.pack('<I%sB'%length, length, *_x))
00737 else:
00738 buff.write(struct.pack('<I%ss'%length, length, _x))
00739 _x = self
00740 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))
00741 _x = self.action_goal.goal.disparity_image.header.frame_id
00742 length = len(_x)
00743 if python3 or type(_x) == unicode:
00744 _x = _x.encode('utf-8')
00745 length = len(_x)
00746 buff.write(struct.pack('<I%ss'%length, length, _x))
00747 _x = self
00748 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))
00749 _x = self.action_goal.goal.disparity_image.image.header.frame_id
00750 length = len(_x)
00751 if python3 or type(_x) == unicode:
00752 _x = _x.encode('utf-8')
00753 length = len(_x)
00754 buff.write(struct.pack('<I%ss'%length, length, _x))
00755 _x = self
00756 buff.write(_struct_2I.pack(_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width))
00757 _x = self.action_goal.goal.disparity_image.image.encoding
00758 length = len(_x)
00759 if python3 or type(_x) == unicode:
00760 _x = _x.encode('utf-8')
00761 length = len(_x)
00762 buff.write(struct.pack('<I%ss'%length, length, _x))
00763 _x = self
00764 buff.write(_struct_BI.pack(_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step))
00765 _x = self.action_goal.goal.disparity_image.image.data
00766 length = len(_x)
00767 # - if encoded as a list instead, serialize as bytes instead of string
00768 if type(_x) in [list, tuple]:
00769 buff.write(struct.pack('<I%sB'%length, length, *_x))
00770 else:
00771 buff.write(struct.pack('<I%ss'%length, length, _x))
00772 _x = self
00773 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))
00774 _x = self.action_result.header.frame_id
00775 length = len(_x)
00776 if python3 or type(_x) == unicode:
00777 _x = _x.encode('utf-8')
00778 length = len(_x)
00779 buff.write(struct.pack('<I%ss'%length, length, _x))
00780 _x = self
00781 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00782 _x = self.action_result.status.goal_id.id
00783 length = len(_x)
00784 if python3 or type(_x) == unicode:
00785 _x = _x.encode('utf-8')
00786 length = len(_x)
00787 buff.write(struct.pack('<I%ss'%length, length, _x))
00788 buff.write(_struct_B.pack(self.action_result.status.status))
00789 _x = self.action_result.status.text
00790 length = len(_x)
00791 if python3 or type(_x) == unicode:
00792 _x = _x.encode('utf-8')
00793 length = len(_x)
00794 buff.write(struct.pack('<I%ss'%length, length, _x))
00795 _x = self
00796 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))
00797 _x = self.action_result.result.table.pose.header.frame_id
00798 length = len(_x)
00799 if python3 or type(_x) == unicode:
00800 _x = _x.encode('utf-8')
00801 length = len(_x)
00802 buff.write(struct.pack('<I%ss'%length, length, _x))
00803 _x = self
00804 buff.write(_struct_7d4fb.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, _x.action_result.result.table.convex_hull.type))
00805 length = len(self.action_result.result.table.convex_hull.dimensions)
00806 buff.write(_struct_I.pack(length))
00807 pattern = '<%sd'%length
00808 buff.write(struct.pack(pattern, *self.action_result.result.table.convex_hull.dimensions))
00809 length = len(self.action_result.result.table.convex_hull.triangles)
00810 buff.write(_struct_I.pack(length))
00811 pattern = '<%si'%length
00812 buff.write(struct.pack(pattern, *self.action_result.result.table.convex_hull.triangles))
00813 length = len(self.action_result.result.table.convex_hull.vertices)
00814 buff.write(_struct_I.pack(length))
00815 for val1 in self.action_result.result.table.convex_hull.vertices:
00816 _x = val1
00817 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00818 length = len(self.action_result.result.clusters)
00819 buff.write(_struct_I.pack(length))
00820 for val1 in self.action_result.result.clusters:
00821 _v1 = val1.header
00822 buff.write(_struct_I.pack(_v1.seq))
00823 _v2 = _v1.stamp
00824 _x = _v2
00825 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00826 _x = _v1.frame_id
00827 length = len(_x)
00828 if python3 or type(_x) == unicode:
00829 _x = _x.encode('utf-8')
00830 length = len(_x)
00831 buff.write(struct.pack('<I%ss'%length, length, _x))
00832 length = len(val1.points)
00833 buff.write(_struct_I.pack(length))
00834 for val2 in val1.points:
00835 _x = val2
00836 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00837 length = len(val1.channels)
00838 buff.write(_struct_I.pack(length))
00839 for val2 in val1.channels:
00840 _x = val2.name
00841 length = len(_x)
00842 if python3 or type(_x) == unicode:
00843 _x = _x.encode('utf-8')
00844 length = len(_x)
00845 buff.write(struct.pack('<I%ss'%length, length, _x))
00846 length = len(val2.values)
00847 buff.write(_struct_I.pack(length))
00848 pattern = '<%sf'%length
00849 buff.write(struct.pack(pattern, *val2.values))
00850 _x = self
00851 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))
00852 _x = self.action_feedback.header.frame_id
00853 length = len(_x)
00854 if python3 or type(_x) == unicode:
00855 _x = _x.encode('utf-8')
00856 length = len(_x)
00857 buff.write(struct.pack('<I%ss'%length, length, _x))
00858 _x = self
00859 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00860 _x = self.action_feedback.status.goal_id.id
00861 length = len(_x)
00862 if python3 or type(_x) == unicode:
00863 _x = _x.encode('utf-8')
00864 length = len(_x)
00865 buff.write(struct.pack('<I%ss'%length, length, _x))
00866 buff.write(_struct_B.pack(self.action_feedback.status.status))
00867 _x = self.action_feedback.status.text
00868 length = len(_x)
00869 if python3 or type(_x) == unicode:
00870 _x = _x.encode('utf-8')
00871 length = len(_x)
00872 buff.write(struct.pack('<I%ss'%length, length, _x))
00873 except struct.error as se: self._check_types(se)
00874 except TypeError as te: self._check_types(te)
00875
00876 def deserialize(self, str):
00877 """
00878 unpack serialized message in str into this message instance
00879 :param str: byte array of serialized message, ``str``
00880 """
00881 try:
00882 if self.action_goal is None:
00883 self.action_goal = object_segmentation_gui.msg.ObjectSegmentationGuiActionGoal()
00884 if self.action_result is None:
00885 self.action_result = object_segmentation_gui.msg.ObjectSegmentationGuiActionResult()
00886 if self.action_feedback is None:
00887 self.action_feedback = object_segmentation_gui.msg.ObjectSegmentationGuiActionFeedback()
00888 end = 0
00889 _x = self
00890 start = end
00891 end += 12
00892 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00893 start = end
00894 end += 4
00895 (length,) = _struct_I.unpack(str[start:end])
00896 start = end
00897 end += length
00898 if python3:
00899 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00900 else:
00901 self.action_goal.header.frame_id = str[start:end]
00902 _x = self
00903 start = end
00904 end += 8
00905 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00906 start = end
00907 end += 4
00908 (length,) = _struct_I.unpack(str[start:end])
00909 start = end
00910 end += length
00911 if python3:
00912 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00913 else:
00914 self.action_goal.goal_id.id = str[start:end]
00915 _x = self
00916 start = end
00917 end += 12
00918 (_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])
00919 start = end
00920 end += 4
00921 (length,) = _struct_I.unpack(str[start:end])
00922 start = end
00923 end += length
00924 if python3:
00925 self.action_goal.goal.image.header.frame_id = str[start:end].decode('utf-8')
00926 else:
00927 self.action_goal.goal.image.header.frame_id = str[start:end]
00928 _x = self
00929 start = end
00930 end += 8
00931 (_x.action_goal.goal.image.height, _x.action_goal.goal.image.width,) = _struct_2I.unpack(str[start:end])
00932 start = end
00933 end += 4
00934 (length,) = _struct_I.unpack(str[start:end])
00935 start = end
00936 end += length
00937 if python3:
00938 self.action_goal.goal.image.encoding = str[start:end].decode('utf-8')
00939 else:
00940 self.action_goal.goal.image.encoding = str[start:end]
00941 _x = self
00942 start = end
00943 end += 5
00944 (_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step,) = _struct_BI.unpack(str[start:end])
00945 start = end
00946 end += 4
00947 (length,) = _struct_I.unpack(str[start:end])
00948 start = end
00949 end += length
00950 if python3:
00951 self.action_goal.goal.image.data = str[start:end].decode('utf-8')
00952 else:
00953 self.action_goal.goal.image.data = str[start:end]
00954 _x = self
00955 start = end
00956 end += 12
00957 (_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])
00958 start = end
00959 end += 4
00960 (length,) = _struct_I.unpack(str[start:end])
00961 start = end
00962 end += length
00963 if python3:
00964 self.action_goal.goal.camera_info.header.frame_id = str[start:end].decode('utf-8')
00965 else:
00966 self.action_goal.goal.camera_info.header.frame_id = str[start:end]
00967 _x = self
00968 start = end
00969 end += 8
00970 (_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width,) = _struct_2I.unpack(str[start:end])
00971 start = end
00972 end += 4
00973 (length,) = _struct_I.unpack(str[start:end])
00974 start = end
00975 end += length
00976 if python3:
00977 self.action_goal.goal.camera_info.distortion_model = str[start:end].decode('utf-8')
00978 else:
00979 self.action_goal.goal.camera_info.distortion_model = str[start:end]
00980 start = end
00981 end += 4
00982 (length,) = _struct_I.unpack(str[start:end])
00983 pattern = '<%sd'%length
00984 start = end
00985 end += struct.calcsize(pattern)
00986 self.action_goal.goal.camera_info.D = struct.unpack(pattern, str[start:end])
00987 start = end
00988 end += 72
00989 self.action_goal.goal.camera_info.K = _struct_9d.unpack(str[start:end])
00990 start = end
00991 end += 72
00992 self.action_goal.goal.camera_info.R = _struct_9d.unpack(str[start:end])
00993 start = end
00994 end += 96
00995 self.action_goal.goal.camera_info.P = _struct_12d.unpack(str[start:end])
00996 _x = self
00997 start = end
00998 end += 37
00999 (_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])
01000 self.action_goal.goal.camera_info.roi.do_rectify = bool(self.action_goal.goal.camera_info.roi.do_rectify)
01001 start = end
01002 end += 4
01003 (length,) = _struct_I.unpack(str[start:end])
01004 start = end
01005 end += length
01006 if python3:
01007 self.action_goal.goal.wide_field.header.frame_id = str[start:end].decode('utf-8')
01008 else:
01009 self.action_goal.goal.wide_field.header.frame_id = str[start:end]
01010 _x = self
01011 start = end
01012 end += 8
01013 (_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width,) = _struct_2I.unpack(str[start:end])
01014 start = end
01015 end += 4
01016 (length,) = _struct_I.unpack(str[start:end])
01017 start = end
01018 end += length
01019 if python3:
01020 self.action_goal.goal.wide_field.encoding = str[start:end].decode('utf-8')
01021 else:
01022 self.action_goal.goal.wide_field.encoding = str[start:end]
01023 _x = self
01024 start = end
01025 end += 5
01026 (_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step,) = _struct_BI.unpack(str[start:end])
01027 start = end
01028 end += 4
01029 (length,) = _struct_I.unpack(str[start:end])
01030 start = end
01031 end += length
01032 if python3:
01033 self.action_goal.goal.wide_field.data = str[start:end].decode('utf-8')
01034 else:
01035 self.action_goal.goal.wide_field.data = str[start:end]
01036 _x = self
01037 start = end
01038 end += 12
01039 (_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])
01040 start = end
01041 end += 4
01042 (length,) = _struct_I.unpack(str[start:end])
01043 start = end
01044 end += length
01045 if python3:
01046 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end].decode('utf-8')
01047 else:
01048 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end]
01049 _x = self
01050 start = end
01051 end += 8
01052 (_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width,) = _struct_2I.unpack(str[start:end])
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.wide_camera_info.distortion_model = str[start:end].decode('utf-8')
01060 else:
01061 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end]
01062 start = end
01063 end += 4
01064 (length,) = _struct_I.unpack(str[start:end])
01065 pattern = '<%sd'%length
01066 start = end
01067 end += struct.calcsize(pattern)
01068 self.action_goal.goal.wide_camera_info.D = struct.unpack(pattern, str[start:end])
01069 start = end
01070 end += 72
01071 self.action_goal.goal.wide_camera_info.K = _struct_9d.unpack(str[start:end])
01072 start = end
01073 end += 72
01074 self.action_goal.goal.wide_camera_info.R = _struct_9d.unpack(str[start:end])
01075 start = end
01076 end += 96
01077 self.action_goal.goal.wide_camera_info.P = _struct_12d.unpack(str[start:end])
01078 _x = self
01079 start = end
01080 end += 37
01081 (_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])
01082 self.action_goal.goal.wide_camera_info.roi.do_rectify = bool(self.action_goal.goal.wide_camera_info.roi.do_rectify)
01083 start = end
01084 end += 4
01085 (length,) = _struct_I.unpack(str[start:end])
01086 start = end
01087 end += length
01088 if python3:
01089 self.action_goal.goal.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01090 else:
01091 self.action_goal.goal.point_cloud.header.frame_id = str[start:end]
01092 _x = self
01093 start = end
01094 end += 8
01095 (_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01096 start = end
01097 end += 4
01098 (length,) = _struct_I.unpack(str[start:end])
01099 self.action_goal.goal.point_cloud.fields = []
01100 for i in range(0, length):
01101 val1 = sensor_msgs.msg.PointField()
01102 start = end
01103 end += 4
01104 (length,) = _struct_I.unpack(str[start:end])
01105 start = end
01106 end += length
01107 if python3:
01108 val1.name = str[start:end].decode('utf-8')
01109 else:
01110 val1.name = str[start:end]
01111 _x = val1
01112 start = end
01113 end += 9
01114 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01115 self.action_goal.goal.point_cloud.fields.append(val1)
01116 _x = self
01117 start = end
01118 end += 9
01119 (_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])
01120 self.action_goal.goal.point_cloud.is_bigendian = bool(self.action_goal.goal.point_cloud.is_bigendian)
01121 start = end
01122 end += 4
01123 (length,) = _struct_I.unpack(str[start:end])
01124 start = end
01125 end += length
01126 if python3:
01127 self.action_goal.goal.point_cloud.data = str[start:end].decode('utf-8')
01128 else:
01129 self.action_goal.goal.point_cloud.data = str[start:end]
01130 _x = self
01131 start = end
01132 end += 13
01133 (_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])
01134 self.action_goal.goal.point_cloud.is_dense = bool(self.action_goal.goal.point_cloud.is_dense)
01135 start = end
01136 end += 4
01137 (length,) = _struct_I.unpack(str[start:end])
01138 start = end
01139 end += length
01140 if python3:
01141 self.action_goal.goal.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01142 else:
01143 self.action_goal.goal.disparity_image.header.frame_id = str[start:end]
01144 _x = self
01145 start = end
01146 end += 12
01147 (_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])
01148 start = end
01149 end += 4
01150 (length,) = _struct_I.unpack(str[start:end])
01151 start = end
01152 end += length
01153 if python3:
01154 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end].decode('utf-8')
01155 else:
01156 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end]
01157 _x = self
01158 start = end
01159 end += 8
01160 (_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width,) = _struct_2I.unpack(str[start:end])
01161 start = end
01162 end += 4
01163 (length,) = _struct_I.unpack(str[start:end])
01164 start = end
01165 end += length
01166 if python3:
01167 self.action_goal.goal.disparity_image.image.encoding = str[start:end].decode('utf-8')
01168 else:
01169 self.action_goal.goal.disparity_image.image.encoding = str[start:end]
01170 _x = self
01171 start = end
01172 end += 5
01173 (_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step,) = _struct_BI.unpack(str[start:end])
01174 start = end
01175 end += 4
01176 (length,) = _struct_I.unpack(str[start:end])
01177 start = end
01178 end += length
01179 if python3:
01180 self.action_goal.goal.disparity_image.image.data = str[start:end].decode('utf-8')
01181 else:
01182 self.action_goal.goal.disparity_image.image.data = str[start:end]
01183 _x = self
01184 start = end
01185 end += 49
01186 (_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])
01187 self.action_goal.goal.disparity_image.valid_window.do_rectify = bool(self.action_goal.goal.disparity_image.valid_window.do_rectify)
01188 start = end
01189 end += 4
01190 (length,) = _struct_I.unpack(str[start:end])
01191 start = end
01192 end += length
01193 if python3:
01194 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01195 else:
01196 self.action_result.header.frame_id = str[start:end]
01197 _x = self
01198 start = end
01199 end += 8
01200 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01201 start = end
01202 end += 4
01203 (length,) = _struct_I.unpack(str[start:end])
01204 start = end
01205 end += length
01206 if python3:
01207 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01208 else:
01209 self.action_result.status.goal_id.id = str[start:end]
01210 start = end
01211 end += 1
01212 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01213 start = end
01214 end += 4
01215 (length,) = _struct_I.unpack(str[start:end])
01216 start = end
01217 end += length
01218 if python3:
01219 self.action_result.status.text = str[start:end].decode('utf-8')
01220 else:
01221 self.action_result.status.text = str[start:end]
01222 _x = self
01223 start = end
01224 end += 12
01225 (_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])
01226 start = end
01227 end += 4
01228 (length,) = _struct_I.unpack(str[start:end])
01229 start = end
01230 end += length
01231 if python3:
01232 self.action_result.result.table.pose.header.frame_id = str[start:end].decode('utf-8')
01233 else:
01234 self.action_result.result.table.pose.header.frame_id = str[start:end]
01235 _x = self
01236 start = end
01237 end += 73
01238 (_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, _x.action_result.result.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
01239 start = end
01240 end += 4
01241 (length,) = _struct_I.unpack(str[start:end])
01242 pattern = '<%sd'%length
01243 start = end
01244 end += struct.calcsize(pattern)
01245 self.action_result.result.table.convex_hull.dimensions = struct.unpack(pattern, str[start:end])
01246 start = end
01247 end += 4
01248 (length,) = _struct_I.unpack(str[start:end])
01249 pattern = '<%si'%length
01250 start = end
01251 end += struct.calcsize(pattern)
01252 self.action_result.result.table.convex_hull.triangles = struct.unpack(pattern, str[start:end])
01253 start = end
01254 end += 4
01255 (length,) = _struct_I.unpack(str[start:end])
01256 self.action_result.result.table.convex_hull.vertices = []
01257 for i in range(0, length):
01258 val1 = geometry_msgs.msg.Point()
01259 _x = val1
01260 start = end
01261 end += 24
01262 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01263 self.action_result.result.table.convex_hull.vertices.append(val1)
01264 start = end
01265 end += 4
01266 (length,) = _struct_I.unpack(str[start:end])
01267 self.action_result.result.clusters = []
01268 for i in range(0, length):
01269 val1 = sensor_msgs.msg.PointCloud()
01270 _v3 = val1.header
01271 start = end
01272 end += 4
01273 (_v3.seq,) = _struct_I.unpack(str[start:end])
01274 _v4 = _v3.stamp
01275 _x = _v4
01276 start = end
01277 end += 8
01278 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01279 start = end
01280 end += 4
01281 (length,) = _struct_I.unpack(str[start:end])
01282 start = end
01283 end += length
01284 if python3:
01285 _v3.frame_id = str[start:end].decode('utf-8')
01286 else:
01287 _v3.frame_id = str[start:end]
01288 start = end
01289 end += 4
01290 (length,) = _struct_I.unpack(str[start:end])
01291 val1.points = []
01292 for i in range(0, length):
01293 val2 = geometry_msgs.msg.Point32()
01294 _x = val2
01295 start = end
01296 end += 12
01297 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01298 val1.points.append(val2)
01299 start = end
01300 end += 4
01301 (length,) = _struct_I.unpack(str[start:end])
01302 val1.channels = []
01303 for i in range(0, length):
01304 val2 = sensor_msgs.msg.ChannelFloat32()
01305 start = end
01306 end += 4
01307 (length,) = _struct_I.unpack(str[start:end])
01308 start = end
01309 end += length
01310 if python3:
01311 val2.name = str[start:end].decode('utf-8')
01312 else:
01313 val2.name = str[start:end]
01314 start = end
01315 end += 4
01316 (length,) = _struct_I.unpack(str[start:end])
01317 pattern = '<%sf'%length
01318 start = end
01319 end += struct.calcsize(pattern)
01320 val2.values = struct.unpack(pattern, str[start:end])
01321 val1.channels.append(val2)
01322 self.action_result.result.clusters.append(val1)
01323 _x = self
01324 start = end
01325 end += 16
01326 (_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])
01327 start = end
01328 end += 4
01329 (length,) = _struct_I.unpack(str[start:end])
01330 start = end
01331 end += length
01332 if python3:
01333 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01334 else:
01335 self.action_feedback.header.frame_id = str[start:end]
01336 _x = self
01337 start = end
01338 end += 8
01339 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01340 start = end
01341 end += 4
01342 (length,) = _struct_I.unpack(str[start:end])
01343 start = end
01344 end += length
01345 if python3:
01346 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01347 else:
01348 self.action_feedback.status.goal_id.id = str[start:end]
01349 start = end
01350 end += 1
01351 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01352 start = end
01353 end += 4
01354 (length,) = _struct_I.unpack(str[start:end])
01355 start = end
01356 end += length
01357 if python3:
01358 self.action_feedback.status.text = str[start:end].decode('utf-8')
01359 else:
01360 self.action_feedback.status.text = str[start:end]
01361 return self
01362 except struct.error as e:
01363 raise genpy.DeserializationError(e) #most likely buffer underfill
01364
01365
01366 def serialize_numpy(self, buff, numpy):
01367 """
01368 serialize message with numpy array types into buffer
01369 :param buff: buffer, ``StringIO``
01370 :param numpy: numpy python module
01371 """
01372 try:
01373 _x = self
01374 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
01375 _x = self.action_goal.header.frame_id
01376 length = len(_x)
01377 if python3 or type(_x) == unicode:
01378 _x = _x.encode('utf-8')
01379 length = len(_x)
01380 buff.write(struct.pack('<I%ss'%length, length, _x))
01381 _x = self
01382 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
01383 _x = self.action_goal.goal_id.id
01384 length = len(_x)
01385 if python3 or type(_x) == unicode:
01386 _x = _x.encode('utf-8')
01387 length = len(_x)
01388 buff.write(struct.pack('<I%ss'%length, length, _x))
01389 _x = self
01390 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))
01391 _x = self.action_goal.goal.image.header.frame_id
01392 length = len(_x)
01393 if python3 or type(_x) == unicode:
01394 _x = _x.encode('utf-8')
01395 length = len(_x)
01396 buff.write(struct.pack('<I%ss'%length, length, _x))
01397 _x = self
01398 buff.write(_struct_2I.pack(_x.action_goal.goal.image.height, _x.action_goal.goal.image.width))
01399 _x = self.action_goal.goal.image.encoding
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_BI.pack(_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step))
01407 _x = self.action_goal.goal.image.data
01408 length = len(_x)
01409 # - if encoded as a list instead, serialize as bytes instead of string
01410 if type(_x) in [list, tuple]:
01411 buff.write(struct.pack('<I%sB'%length, length, *_x))
01412 else:
01413 buff.write(struct.pack('<I%ss'%length, length, _x))
01414 _x = self
01415 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))
01416 _x = self.action_goal.goal.camera_info.header.frame_id
01417 length = len(_x)
01418 if python3 or type(_x) == unicode:
01419 _x = _x.encode('utf-8')
01420 length = len(_x)
01421 buff.write(struct.pack('<I%ss'%length, length, _x))
01422 _x = self
01423 buff.write(_struct_2I.pack(_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width))
01424 _x = self.action_goal.goal.camera_info.distortion_model
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 length = len(self.action_goal.goal.camera_info.D)
01431 buff.write(_struct_I.pack(length))
01432 pattern = '<%sd'%length
01433 buff.write(self.action_goal.goal.camera_info.D.tostring())
01434 buff.write(self.action_goal.goal.camera_info.K.tostring())
01435 buff.write(self.action_goal.goal.camera_info.R.tostring())
01436 buff.write(self.action_goal.goal.camera_info.P.tostring())
01437 _x = self
01438 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))
01439 _x = self.action_goal.goal.wide_field.header.frame_id
01440 length = len(_x)
01441 if python3 or type(_x) == unicode:
01442 _x = _x.encode('utf-8')
01443 length = len(_x)
01444 buff.write(struct.pack('<I%ss'%length, length, _x))
01445 _x = self
01446 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width))
01447 _x = self.action_goal.goal.wide_field.encoding
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_BI.pack(_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step))
01455 _x = self.action_goal.goal.wide_field.data
01456 length = len(_x)
01457 # - if encoded as a list instead, serialize as bytes instead of string
01458 if type(_x) in [list, tuple]:
01459 buff.write(struct.pack('<I%sB'%length, length, *_x))
01460 else:
01461 buff.write(struct.pack('<I%ss'%length, length, _x))
01462 _x = self
01463 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))
01464 _x = self.action_goal.goal.wide_camera_info.header.frame_id
01465 length = len(_x)
01466 if python3 or type(_x) == unicode:
01467 _x = _x.encode('utf-8')
01468 length = len(_x)
01469 buff.write(struct.pack('<I%ss'%length, length, _x))
01470 _x = self
01471 buff.write(_struct_2I.pack(_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width))
01472 _x = self.action_goal.goal.wide_camera_info.distortion_model
01473 length = len(_x)
01474 if python3 or type(_x) == unicode:
01475 _x = _x.encode('utf-8')
01476 length = len(_x)
01477 buff.write(struct.pack('<I%ss'%length, length, _x))
01478 length = len(self.action_goal.goal.wide_camera_info.D)
01479 buff.write(_struct_I.pack(length))
01480 pattern = '<%sd'%length
01481 buff.write(self.action_goal.goal.wide_camera_info.D.tostring())
01482 buff.write(self.action_goal.goal.wide_camera_info.K.tostring())
01483 buff.write(self.action_goal.goal.wide_camera_info.R.tostring())
01484 buff.write(self.action_goal.goal.wide_camera_info.P.tostring())
01485 _x = self
01486 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))
01487 _x = self.action_goal.goal.point_cloud.header.frame_id
01488 length = len(_x)
01489 if python3 or type(_x) == unicode:
01490 _x = _x.encode('utf-8')
01491 length = len(_x)
01492 buff.write(struct.pack('<I%ss'%length, length, _x))
01493 _x = self
01494 buff.write(_struct_2I.pack(_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width))
01495 length = len(self.action_goal.goal.point_cloud.fields)
01496 buff.write(_struct_I.pack(length))
01497 for val1 in self.action_goal.goal.point_cloud.fields:
01498 _x = val1.name
01499 length = len(_x)
01500 if python3 or type(_x) == unicode:
01501 _x = _x.encode('utf-8')
01502 length = len(_x)
01503 buff.write(struct.pack('<I%ss'%length, length, _x))
01504 _x = val1
01505 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01506 _x = self
01507 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))
01508 _x = self.action_goal.goal.point_cloud.data
01509 length = len(_x)
01510 # - if encoded as a list instead, serialize as bytes instead of string
01511 if type(_x) in [list, tuple]:
01512 buff.write(struct.pack('<I%sB'%length, length, *_x))
01513 else:
01514 buff.write(struct.pack('<I%ss'%length, length, _x))
01515 _x = self
01516 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))
01517 _x = self.action_goal.goal.disparity_image.header.frame_id
01518 length = len(_x)
01519 if python3 or type(_x) == unicode:
01520 _x = _x.encode('utf-8')
01521 length = len(_x)
01522 buff.write(struct.pack('<I%ss'%length, length, _x))
01523 _x = self
01524 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))
01525 _x = self.action_goal.goal.disparity_image.image.header.frame_id
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_2I.pack(_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width))
01533 _x = self.action_goal.goal.disparity_image.image.encoding
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_BI.pack(_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step))
01541 _x = self.action_goal.goal.disparity_image.image.data
01542 length = len(_x)
01543 # - if encoded as a list instead, serialize as bytes instead of string
01544 if type(_x) in [list, tuple]:
01545 buff.write(struct.pack('<I%sB'%length, length, *_x))
01546 else:
01547 buff.write(struct.pack('<I%ss'%length, length, _x))
01548 _x = self
01549 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))
01550 _x = self.action_result.header.frame_id
01551 length = len(_x)
01552 if python3 or type(_x) == unicode:
01553 _x = _x.encode('utf-8')
01554 length = len(_x)
01555 buff.write(struct.pack('<I%ss'%length, length, _x))
01556 _x = self
01557 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
01558 _x = self.action_result.status.goal_id.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 buff.write(_struct_B.pack(self.action_result.status.status))
01565 _x = self.action_result.status.text
01566 length = len(_x)
01567 if python3 or type(_x) == unicode:
01568 _x = _x.encode('utf-8')
01569 length = len(_x)
01570 buff.write(struct.pack('<I%ss'%length, length, _x))
01571 _x = self
01572 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))
01573 _x = self.action_result.result.table.pose.header.frame_id
01574 length = len(_x)
01575 if python3 or type(_x) == unicode:
01576 _x = _x.encode('utf-8')
01577 length = len(_x)
01578 buff.write(struct.pack('<I%ss'%length, length, _x))
01579 _x = self
01580 buff.write(_struct_7d4fb.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, _x.action_result.result.table.convex_hull.type))
01581 length = len(self.action_result.result.table.convex_hull.dimensions)
01582 buff.write(_struct_I.pack(length))
01583 pattern = '<%sd'%length
01584 buff.write(self.action_result.result.table.convex_hull.dimensions.tostring())
01585 length = len(self.action_result.result.table.convex_hull.triangles)
01586 buff.write(_struct_I.pack(length))
01587 pattern = '<%si'%length
01588 buff.write(self.action_result.result.table.convex_hull.triangles.tostring())
01589 length = len(self.action_result.result.table.convex_hull.vertices)
01590 buff.write(_struct_I.pack(length))
01591 for val1 in self.action_result.result.table.convex_hull.vertices:
01592 _x = val1
01593 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01594 length = len(self.action_result.result.clusters)
01595 buff.write(_struct_I.pack(length))
01596 for val1 in self.action_result.result.clusters:
01597 _v5 = val1.header
01598 buff.write(_struct_I.pack(_v5.seq))
01599 _v6 = _v5.stamp
01600 _x = _v6
01601 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01602 _x = _v5.frame_id
01603 length = len(_x)
01604 if python3 or type(_x) == unicode:
01605 _x = _x.encode('utf-8')
01606 length = len(_x)
01607 buff.write(struct.pack('<I%ss'%length, length, _x))
01608 length = len(val1.points)
01609 buff.write(_struct_I.pack(length))
01610 for val2 in val1.points:
01611 _x = val2
01612 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01613 length = len(val1.channels)
01614 buff.write(_struct_I.pack(length))
01615 for val2 in val1.channels:
01616 _x = val2.name
01617 length = len(_x)
01618 if python3 or type(_x) == unicode:
01619 _x = _x.encode('utf-8')
01620 length = len(_x)
01621 buff.write(struct.pack('<I%ss'%length, length, _x))
01622 length = len(val2.values)
01623 buff.write(_struct_I.pack(length))
01624 pattern = '<%sf'%length
01625 buff.write(val2.values.tostring())
01626 _x = self
01627 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))
01628 _x = self.action_feedback.header.frame_id
01629 length = len(_x)
01630 if python3 or type(_x) == unicode:
01631 _x = _x.encode('utf-8')
01632 length = len(_x)
01633 buff.write(struct.pack('<I%ss'%length, length, _x))
01634 _x = self
01635 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
01636 _x = self.action_feedback.status.goal_id.id
01637 length = len(_x)
01638 if python3 or type(_x) == unicode:
01639 _x = _x.encode('utf-8')
01640 length = len(_x)
01641 buff.write(struct.pack('<I%ss'%length, length, _x))
01642 buff.write(_struct_B.pack(self.action_feedback.status.status))
01643 _x = self.action_feedback.status.text
01644 length = len(_x)
01645 if python3 or type(_x) == unicode:
01646 _x = _x.encode('utf-8')
01647 length = len(_x)
01648 buff.write(struct.pack('<I%ss'%length, length, _x))
01649 except struct.error as se: self._check_types(se)
01650 except TypeError as te: self._check_types(te)
01651
01652 def deserialize_numpy(self, str, numpy):
01653 """
01654 unpack serialized message in str into this message instance using numpy for array types
01655 :param str: byte array of serialized message, ``str``
01656 :param numpy: numpy python module
01657 """
01658 try:
01659 if self.action_goal is None:
01660 self.action_goal = object_segmentation_gui.msg.ObjectSegmentationGuiActionGoal()
01661 if self.action_result is None:
01662 self.action_result = object_segmentation_gui.msg.ObjectSegmentationGuiActionResult()
01663 if self.action_feedback is None:
01664 self.action_feedback = object_segmentation_gui.msg.ObjectSegmentationGuiActionFeedback()
01665 end = 0
01666 _x = self
01667 start = end
01668 end += 12
01669 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01670 start = end
01671 end += 4
01672 (length,) = _struct_I.unpack(str[start:end])
01673 start = end
01674 end += length
01675 if python3:
01676 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
01677 else:
01678 self.action_goal.header.frame_id = str[start:end]
01679 _x = self
01680 start = end
01681 end += 8
01682 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01683 start = end
01684 end += 4
01685 (length,) = _struct_I.unpack(str[start:end])
01686 start = end
01687 end += length
01688 if python3:
01689 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
01690 else:
01691 self.action_goal.goal_id.id = str[start:end]
01692 _x = self
01693 start = end
01694 end += 12
01695 (_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])
01696 start = end
01697 end += 4
01698 (length,) = _struct_I.unpack(str[start:end])
01699 start = end
01700 end += length
01701 if python3:
01702 self.action_goal.goal.image.header.frame_id = str[start:end].decode('utf-8')
01703 else:
01704 self.action_goal.goal.image.header.frame_id = str[start:end]
01705 _x = self
01706 start = end
01707 end += 8
01708 (_x.action_goal.goal.image.height, _x.action_goal.goal.image.width,) = _struct_2I.unpack(str[start:end])
01709 start = end
01710 end += 4
01711 (length,) = _struct_I.unpack(str[start:end])
01712 start = end
01713 end += length
01714 if python3:
01715 self.action_goal.goal.image.encoding = str[start:end].decode('utf-8')
01716 else:
01717 self.action_goal.goal.image.encoding = str[start:end]
01718 _x = self
01719 start = end
01720 end += 5
01721 (_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step,) = _struct_BI.unpack(str[start:end])
01722 start = end
01723 end += 4
01724 (length,) = _struct_I.unpack(str[start:end])
01725 start = end
01726 end += length
01727 if python3:
01728 self.action_goal.goal.image.data = str[start:end].decode('utf-8')
01729 else:
01730 self.action_goal.goal.image.data = str[start:end]
01731 _x = self
01732 start = end
01733 end += 12
01734 (_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])
01735 start = end
01736 end += 4
01737 (length,) = _struct_I.unpack(str[start:end])
01738 start = end
01739 end += length
01740 if python3:
01741 self.action_goal.goal.camera_info.header.frame_id = str[start:end].decode('utf-8')
01742 else:
01743 self.action_goal.goal.camera_info.header.frame_id = str[start:end]
01744 _x = self
01745 start = end
01746 end += 8
01747 (_x.action_goal.goal.camera_info.height, _x.action_goal.goal.camera_info.width,) = _struct_2I.unpack(str[start:end])
01748 start = end
01749 end += 4
01750 (length,) = _struct_I.unpack(str[start:end])
01751 start = end
01752 end += length
01753 if python3:
01754 self.action_goal.goal.camera_info.distortion_model = str[start:end].decode('utf-8')
01755 else:
01756 self.action_goal.goal.camera_info.distortion_model = str[start:end]
01757 start = end
01758 end += 4
01759 (length,) = _struct_I.unpack(str[start:end])
01760 pattern = '<%sd'%length
01761 start = end
01762 end += struct.calcsize(pattern)
01763 self.action_goal.goal.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01764 start = end
01765 end += 72
01766 self.action_goal.goal.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01767 start = end
01768 end += 72
01769 self.action_goal.goal.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01770 start = end
01771 end += 96
01772 self.action_goal.goal.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01773 _x = self
01774 start = end
01775 end += 37
01776 (_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])
01777 self.action_goal.goal.camera_info.roi.do_rectify = bool(self.action_goal.goal.camera_info.roi.do_rectify)
01778 start = end
01779 end += 4
01780 (length,) = _struct_I.unpack(str[start:end])
01781 start = end
01782 end += length
01783 if python3:
01784 self.action_goal.goal.wide_field.header.frame_id = str[start:end].decode('utf-8')
01785 else:
01786 self.action_goal.goal.wide_field.header.frame_id = str[start:end]
01787 _x = self
01788 start = end
01789 end += 8
01790 (_x.action_goal.goal.wide_field.height, _x.action_goal.goal.wide_field.width,) = _struct_2I.unpack(str[start:end])
01791 start = end
01792 end += 4
01793 (length,) = _struct_I.unpack(str[start:end])
01794 start = end
01795 end += length
01796 if python3:
01797 self.action_goal.goal.wide_field.encoding = str[start:end].decode('utf-8')
01798 else:
01799 self.action_goal.goal.wide_field.encoding = str[start:end]
01800 _x = self
01801 start = end
01802 end += 5
01803 (_x.action_goal.goal.wide_field.is_bigendian, _x.action_goal.goal.wide_field.step,) = _struct_BI.unpack(str[start:end])
01804 start = end
01805 end += 4
01806 (length,) = _struct_I.unpack(str[start:end])
01807 start = end
01808 end += length
01809 if python3:
01810 self.action_goal.goal.wide_field.data = str[start:end].decode('utf-8')
01811 else:
01812 self.action_goal.goal.wide_field.data = str[start:end]
01813 _x = self
01814 start = end
01815 end += 12
01816 (_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])
01817 start = end
01818 end += 4
01819 (length,) = _struct_I.unpack(str[start:end])
01820 start = end
01821 end += length
01822 if python3:
01823 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end].decode('utf-8')
01824 else:
01825 self.action_goal.goal.wide_camera_info.header.frame_id = str[start:end]
01826 _x = self
01827 start = end
01828 end += 8
01829 (_x.action_goal.goal.wide_camera_info.height, _x.action_goal.goal.wide_camera_info.width,) = _struct_2I.unpack(str[start:end])
01830 start = end
01831 end += 4
01832 (length,) = _struct_I.unpack(str[start:end])
01833 start = end
01834 end += length
01835 if python3:
01836 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end].decode('utf-8')
01837 else:
01838 self.action_goal.goal.wide_camera_info.distortion_model = str[start:end]
01839 start = end
01840 end += 4
01841 (length,) = _struct_I.unpack(str[start:end])
01842 pattern = '<%sd'%length
01843 start = end
01844 end += struct.calcsize(pattern)
01845 self.action_goal.goal.wide_camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01846 start = end
01847 end += 72
01848 self.action_goal.goal.wide_camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01849 start = end
01850 end += 72
01851 self.action_goal.goal.wide_camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01852 start = end
01853 end += 96
01854 self.action_goal.goal.wide_camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01855 _x = self
01856 start = end
01857 end += 37
01858 (_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])
01859 self.action_goal.goal.wide_camera_info.roi.do_rectify = bool(self.action_goal.goal.wide_camera_info.roi.do_rectify)
01860 start = end
01861 end += 4
01862 (length,) = _struct_I.unpack(str[start:end])
01863 start = end
01864 end += length
01865 if python3:
01866 self.action_goal.goal.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01867 else:
01868 self.action_goal.goal.point_cloud.header.frame_id = str[start:end]
01869 _x = self
01870 start = end
01871 end += 8
01872 (_x.action_goal.goal.point_cloud.height, _x.action_goal.goal.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01873 start = end
01874 end += 4
01875 (length,) = _struct_I.unpack(str[start:end])
01876 self.action_goal.goal.point_cloud.fields = []
01877 for i in range(0, length):
01878 val1 = sensor_msgs.msg.PointField()
01879 start = end
01880 end += 4
01881 (length,) = _struct_I.unpack(str[start:end])
01882 start = end
01883 end += length
01884 if python3:
01885 val1.name = str[start:end].decode('utf-8')
01886 else:
01887 val1.name = str[start:end]
01888 _x = val1
01889 start = end
01890 end += 9
01891 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01892 self.action_goal.goal.point_cloud.fields.append(val1)
01893 _x = self
01894 start = end
01895 end += 9
01896 (_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])
01897 self.action_goal.goal.point_cloud.is_bigendian = bool(self.action_goal.goal.point_cloud.is_bigendian)
01898 start = end
01899 end += 4
01900 (length,) = _struct_I.unpack(str[start:end])
01901 start = end
01902 end += length
01903 if python3:
01904 self.action_goal.goal.point_cloud.data = str[start:end].decode('utf-8')
01905 else:
01906 self.action_goal.goal.point_cloud.data = str[start:end]
01907 _x = self
01908 start = end
01909 end += 13
01910 (_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])
01911 self.action_goal.goal.point_cloud.is_dense = bool(self.action_goal.goal.point_cloud.is_dense)
01912 start = end
01913 end += 4
01914 (length,) = _struct_I.unpack(str[start:end])
01915 start = end
01916 end += length
01917 if python3:
01918 self.action_goal.goal.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01919 else:
01920 self.action_goal.goal.disparity_image.header.frame_id = str[start:end]
01921 _x = self
01922 start = end
01923 end += 12
01924 (_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])
01925 start = end
01926 end += 4
01927 (length,) = _struct_I.unpack(str[start:end])
01928 start = end
01929 end += length
01930 if python3:
01931 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end].decode('utf-8')
01932 else:
01933 self.action_goal.goal.disparity_image.image.header.frame_id = str[start:end]
01934 _x = self
01935 start = end
01936 end += 8
01937 (_x.action_goal.goal.disparity_image.image.height, _x.action_goal.goal.disparity_image.image.width,) = _struct_2I.unpack(str[start:end])
01938 start = end
01939 end += 4
01940 (length,) = _struct_I.unpack(str[start:end])
01941 start = end
01942 end += length
01943 if python3:
01944 self.action_goal.goal.disparity_image.image.encoding = str[start:end].decode('utf-8')
01945 else:
01946 self.action_goal.goal.disparity_image.image.encoding = str[start:end]
01947 _x = self
01948 start = end
01949 end += 5
01950 (_x.action_goal.goal.disparity_image.image.is_bigendian, _x.action_goal.goal.disparity_image.image.step,) = _struct_BI.unpack(str[start:end])
01951 start = end
01952 end += 4
01953 (length,) = _struct_I.unpack(str[start:end])
01954 start = end
01955 end += length
01956 if python3:
01957 self.action_goal.goal.disparity_image.image.data = str[start:end].decode('utf-8')
01958 else:
01959 self.action_goal.goal.disparity_image.image.data = str[start:end]
01960 _x = self
01961 start = end
01962 end += 49
01963 (_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])
01964 self.action_goal.goal.disparity_image.valid_window.do_rectify = bool(self.action_goal.goal.disparity_image.valid_window.do_rectify)
01965 start = end
01966 end += 4
01967 (length,) = _struct_I.unpack(str[start:end])
01968 start = end
01969 end += length
01970 if python3:
01971 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01972 else:
01973 self.action_result.header.frame_id = str[start:end]
01974 _x = self
01975 start = end
01976 end += 8
01977 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01978 start = end
01979 end += 4
01980 (length,) = _struct_I.unpack(str[start:end])
01981 start = end
01982 end += length
01983 if python3:
01984 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01985 else:
01986 self.action_result.status.goal_id.id = str[start:end]
01987 start = end
01988 end += 1
01989 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01990 start = end
01991 end += 4
01992 (length,) = _struct_I.unpack(str[start:end])
01993 start = end
01994 end += length
01995 if python3:
01996 self.action_result.status.text = str[start:end].decode('utf-8')
01997 else:
01998 self.action_result.status.text = str[start:end]
01999 _x = self
02000 start = end
02001 end += 12
02002 (_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])
02003 start = end
02004 end += 4
02005 (length,) = _struct_I.unpack(str[start:end])
02006 start = end
02007 end += length
02008 if python3:
02009 self.action_result.result.table.pose.header.frame_id = str[start:end].decode('utf-8')
02010 else:
02011 self.action_result.result.table.pose.header.frame_id = str[start:end]
02012 _x = self
02013 start = end
02014 end += 73
02015 (_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, _x.action_result.result.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
02016 start = end
02017 end += 4
02018 (length,) = _struct_I.unpack(str[start:end])
02019 pattern = '<%sd'%length
02020 start = end
02021 end += struct.calcsize(pattern)
02022 self.action_result.result.table.convex_hull.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02023 start = end
02024 end += 4
02025 (length,) = _struct_I.unpack(str[start:end])
02026 pattern = '<%si'%length
02027 start = end
02028 end += struct.calcsize(pattern)
02029 self.action_result.result.table.convex_hull.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02030 start = end
02031 end += 4
02032 (length,) = _struct_I.unpack(str[start:end])
02033 self.action_result.result.table.convex_hull.vertices = []
02034 for i in range(0, length):
02035 val1 = geometry_msgs.msg.Point()
02036 _x = val1
02037 start = end
02038 end += 24
02039 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02040 self.action_result.result.table.convex_hull.vertices.append(val1)
02041 start = end
02042 end += 4
02043 (length,) = _struct_I.unpack(str[start:end])
02044 self.action_result.result.clusters = []
02045 for i in range(0, length):
02046 val1 = sensor_msgs.msg.PointCloud()
02047 _v7 = val1.header
02048 start = end
02049 end += 4
02050 (_v7.seq,) = _struct_I.unpack(str[start:end])
02051 _v8 = _v7.stamp
02052 _x = _v8
02053 start = end
02054 end += 8
02055 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02056 start = end
02057 end += 4
02058 (length,) = _struct_I.unpack(str[start:end])
02059 start = end
02060 end += length
02061 if python3:
02062 _v7.frame_id = str[start:end].decode('utf-8')
02063 else:
02064 _v7.frame_id = str[start:end]
02065 start = end
02066 end += 4
02067 (length,) = _struct_I.unpack(str[start:end])
02068 val1.points = []
02069 for i in range(0, length):
02070 val2 = geometry_msgs.msg.Point32()
02071 _x = val2
02072 start = end
02073 end += 12
02074 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02075 val1.points.append(val2)
02076 start = end
02077 end += 4
02078 (length,) = _struct_I.unpack(str[start:end])
02079 val1.channels = []
02080 for i in range(0, length):
02081 val2 = sensor_msgs.msg.ChannelFloat32()
02082 start = end
02083 end += 4
02084 (length,) = _struct_I.unpack(str[start:end])
02085 start = end
02086 end += length
02087 if python3:
02088 val2.name = str[start:end].decode('utf-8')
02089 else:
02090 val2.name = str[start:end]
02091 start = end
02092 end += 4
02093 (length,) = _struct_I.unpack(str[start:end])
02094 pattern = '<%sf'%length
02095 start = end
02096 end += struct.calcsize(pattern)
02097 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
02098 val1.channels.append(val2)
02099 self.action_result.result.clusters.append(val1)
02100 _x = self
02101 start = end
02102 end += 16
02103 (_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])
02104 start = end
02105 end += 4
02106 (length,) = _struct_I.unpack(str[start:end])
02107 start = end
02108 end += length
02109 if python3:
02110 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
02111 else:
02112 self.action_feedback.header.frame_id = str[start:end]
02113 _x = self
02114 start = end
02115 end += 8
02116 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02117 start = end
02118 end += 4
02119 (length,) = _struct_I.unpack(str[start:end])
02120 start = end
02121 end += length
02122 if python3:
02123 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
02124 else:
02125 self.action_feedback.status.goal_id.id = str[start:end]
02126 start = end
02127 end += 1
02128 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
02129 start = end
02130 end += 4
02131 (length,) = _struct_I.unpack(str[start:end])
02132 start = end
02133 end += length
02134 if python3:
02135 self.action_feedback.status.text = str[start:end].decode('utf-8')
02136 else:
02137 self.action_feedback.status.text = str[start:end]
02138 return self
02139 except struct.error as e:
02140 raise genpy.DeserializationError(e) #most likely buffer underfill
02141
02142 _struct_I = genpy.struct_I
02143 _struct_IBI = struct.Struct("<IBI")
02144 _struct_6IB3I = struct.Struct("<6IB3I")
02145 _struct_B = struct.Struct("<B")
02146 _struct_12d = struct.Struct("<12d")
02147 _struct_9d = struct.Struct("<9d")
02148 _struct_7d4fb = struct.Struct("<7d4fb")
02149 _struct_BI = struct.Struct("<BI")
02150 _struct_3f = struct.Struct("<3f")
02151 _struct_3I = struct.Struct("<3I")
02152 _struct_B3I = struct.Struct("<B3I")
02153 _struct_B2I = struct.Struct("<B2I")
02154 _struct_2f4IB3f3I = struct.Struct("<2f4IB3f3I")
02155 _struct_i3I = struct.Struct("<i3I")
02156 _struct_2I = struct.Struct("<2I")
02157 _struct_3d = struct.Struct("<3d")