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