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