$search
00001 """autogenerated by genmsg_py from GetGripperPoseGoal.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import sensor_msgs.msg 00006 import geometry_msgs.msg 00007 import object_manipulation_msgs.msg 00008 import household_objects_database_msgs.msg 00009 import std_msgs.msg 00010 00011 class GetGripperPoseGoal(roslib.message.Message): 00012 _md5sum = "7ca516fef9c15991c035b01ff6268377" 00013 _type = "pr2_object_manipulation_msgs/GetGripperPoseGoal" 00014 _has_header = False #flag to mark the presence of a Header object 00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00016 00017 # for which arm are we requesting a pose 00018 # useful for knowing which arm to initialize from when seed is empty 00019 string arm_name 00020 00021 # a seed position for the ghosted gripper. If emtpy (quaternion of norm 0) 00022 # the ghosted gripper will be initialized at the current position of the gripper 00023 geometry_msgs/PoseStamped gripper_pose 00024 float32 gripper_opening 00025 00026 # An object that the gripper is holding. May be empty. 00027 object_manipulation_msgs/GraspableObject object 00028 00029 # how we are holding the object, if any. 00030 object_manipulation_msgs/Grasp grasp 00031 00032 00033 ================================================================================ 00034 MSG: geometry_msgs/PoseStamped 00035 # A Pose with reference coordinate frame and timestamp 00036 Header header 00037 Pose pose 00038 00039 ================================================================================ 00040 MSG: std_msgs/Header 00041 # Standard metadata for higher-level stamped data types. 00042 # This is generally used to communicate timestamped data 00043 # in a particular coordinate frame. 00044 # 00045 # sequence ID: consecutively increasing ID 00046 uint32 seq 00047 #Two-integer timestamp that is expressed as: 00048 # * stamp.secs: seconds (stamp_secs) since epoch 00049 # * stamp.nsecs: nanoseconds since stamp_secs 00050 # time-handling sugar is provided by the client library 00051 time stamp 00052 #Frame this data is associated with 00053 # 0: no frame 00054 # 1: global frame 00055 string frame_id 00056 00057 ================================================================================ 00058 MSG: geometry_msgs/Pose 00059 # A representation of pose in free space, composed of postion and orientation. 00060 Point position 00061 Quaternion orientation 00062 00063 ================================================================================ 00064 MSG: geometry_msgs/Point 00065 # This contains the position of a point in free space 00066 float64 x 00067 float64 y 00068 float64 z 00069 00070 ================================================================================ 00071 MSG: geometry_msgs/Quaternion 00072 # This represents an orientation in free space in quaternion form. 00073 00074 float64 x 00075 float64 y 00076 float64 z 00077 float64 w 00078 00079 ================================================================================ 00080 MSG: object_manipulation_msgs/GraspableObject 00081 # an object that the object_manipulator can work on 00082 00083 # a graspable object can be represented in multiple ways. This message 00084 # can contain all of them. Which one is actually used is up to the receiver 00085 # of this message. When adding new representations, one must be careful that 00086 # they have reasonable lightweight defaults indicating that that particular 00087 # representation is not available. 00088 00089 # the tf frame to be used as a reference frame when combining information from 00090 # the different representations below 00091 string reference_frame_id 00092 00093 # potential recognition results from a database of models 00094 # all poses are relative to the object reference pose 00095 household_objects_database_msgs/DatabaseModelPose[] potential_models 00096 00097 # the point cloud itself 00098 sensor_msgs/PointCloud cluster 00099 00100 # a region of a PointCloud2 of interest 00101 object_manipulation_msgs/SceneRegion region 00102 00103 # the name that this object has in the collision environment 00104 string collision_name 00105 ================================================================================ 00106 MSG: household_objects_database_msgs/DatabaseModelPose 00107 # Informs that a specific model from the Model Database has been 00108 # identified at a certain location 00109 00110 # the database id of the model 00111 int32 model_id 00112 00113 # the pose that it can be found in 00114 geometry_msgs/PoseStamped pose 00115 00116 # a measure of the confidence level in this detection result 00117 float32 confidence 00118 00119 # the name of the object detector that generated this detection result 00120 string detector_name 00121 00122 ================================================================================ 00123 MSG: sensor_msgs/PointCloud 00124 # This message holds a collection of 3d points, plus optional additional 00125 # information about each point. 00126 00127 # Time of sensor data acquisition, coordinate frame ID. 00128 Header header 00129 00130 # Array of 3d points. Each Point32 should be interpreted as a 3d point 00131 # in the frame given in the header. 00132 geometry_msgs/Point32[] points 00133 00134 # Each channel should have the same number of elements as points array, 00135 # and the data in each channel should correspond 1:1 with each point. 00136 # Channel names in common practice are listed in ChannelFloat32.msg. 00137 ChannelFloat32[] channels 00138 00139 ================================================================================ 00140 MSG: geometry_msgs/Point32 00141 # This contains the position of a point in free space(with 32 bits of precision). 00142 # It is recommeded to use Point wherever possible instead of Point32. 00143 # 00144 # This recommendation is to promote interoperability. 00145 # 00146 # This message is designed to take up less space when sending 00147 # lots of points at once, as in the case of a PointCloud. 00148 00149 float32 x 00150 float32 y 00151 float32 z 00152 ================================================================================ 00153 MSG: sensor_msgs/ChannelFloat32 00154 # This message is used by the PointCloud message to hold optional data 00155 # associated with each point in the cloud. The length of the values 00156 # array should be the same as the length of the points array in the 00157 # PointCloud, and each value should be associated with the corresponding 00158 # point. 00159 00160 # Channel names in existing practice include: 00161 # "u", "v" - row and column (respectively) in the left stereo image. 00162 # This is opposite to usual conventions but remains for 00163 # historical reasons. The newer PointCloud2 message has no 00164 # such problem. 00165 # "rgb" - For point clouds produced by color stereo cameras. uint8 00166 # (R,G,B) values packed into the least significant 24 bits, 00167 # in order. 00168 # "intensity" - laser or pixel intensity. 00169 # "distance" 00170 00171 # The channel name should give semantics of the channel (e.g. 00172 # "intensity" instead of "value"). 00173 string name 00174 00175 # The values array should be 1-1 with the elements of the associated 00176 # PointCloud. 00177 float32[] values 00178 00179 ================================================================================ 00180 MSG: object_manipulation_msgs/SceneRegion 00181 # Point cloud 00182 sensor_msgs/PointCloud2 cloud 00183 00184 # Indices for the region of interest 00185 int32[] mask 00186 00187 # One of the corresponding 2D images, if applicable 00188 sensor_msgs/Image image 00189 00190 # The disparity image, if applicable 00191 sensor_msgs/Image disparity_image 00192 00193 # Camera info for the camera that took the image 00194 sensor_msgs/CameraInfo cam_info 00195 00196 # a 3D region of interest for grasp planning 00197 geometry_msgs/PoseStamped roi_box_pose 00198 geometry_msgs/Vector3 roi_box_dims 00199 00200 ================================================================================ 00201 MSG: sensor_msgs/PointCloud2 00202 # This message holds a collection of N-dimensional points, which may 00203 # contain additional information such as normals, intensity, etc. The 00204 # point data is stored as a binary blob, its layout described by the 00205 # contents of the "fields" array. 00206 00207 # The point cloud data may be organized 2d (image-like) or 1d 00208 # (unordered). Point clouds organized as 2d images may be produced by 00209 # camera depth sensors such as stereo or time-of-flight. 00210 00211 # Time of sensor data acquisition, and the coordinate frame ID (for 3d 00212 # points). 00213 Header header 00214 00215 # 2D structure of the point cloud. If the cloud is unordered, height is 00216 # 1 and width is the length of the point cloud. 00217 uint32 height 00218 uint32 width 00219 00220 # Describes the channels and their layout in the binary data blob. 00221 PointField[] fields 00222 00223 bool is_bigendian # Is this data bigendian? 00224 uint32 point_step # Length of a point in bytes 00225 uint32 row_step # Length of a row in bytes 00226 uint8[] data # Actual point data, size is (row_step*height) 00227 00228 bool is_dense # True if there are no invalid points 00229 00230 ================================================================================ 00231 MSG: sensor_msgs/PointField 00232 # This message holds the description of one point entry in the 00233 # PointCloud2 message format. 00234 uint8 INT8 = 1 00235 uint8 UINT8 = 2 00236 uint8 INT16 = 3 00237 uint8 UINT16 = 4 00238 uint8 INT32 = 5 00239 uint8 UINT32 = 6 00240 uint8 FLOAT32 = 7 00241 uint8 FLOAT64 = 8 00242 00243 string name # Name of field 00244 uint32 offset # Offset from start of point struct 00245 uint8 datatype # Datatype enumeration, see above 00246 uint32 count # How many elements in the field 00247 00248 ================================================================================ 00249 MSG: sensor_msgs/Image 00250 # This message contains an uncompressed image 00251 # (0, 0) is at top-left corner of image 00252 # 00253 00254 Header header # Header timestamp should be acquisition time of image 00255 # Header frame_id should be optical frame of camera 00256 # origin of frame should be optical center of cameara 00257 # +x should point to the right in the image 00258 # +y should point down in the image 00259 # +z should point into to plane of the image 00260 # If the frame_id here and the frame_id of the CameraInfo 00261 # message associated with the image conflict 00262 # the behavior is undefined 00263 00264 uint32 height # image height, that is, number of rows 00265 uint32 width # image width, that is, number of columns 00266 00267 # The legal values for encoding are in file src/image_encodings.cpp 00268 # If you want to standardize a new string format, join 00269 # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 00270 00271 string encoding # Encoding of pixels -- channel meaning, ordering, size 00272 # taken from the list of strings in src/image_encodings.cpp 00273 00274 uint8 is_bigendian # is this data bigendian? 00275 uint32 step # Full row length in bytes 00276 uint8[] data # actual matrix data, size is (step * rows) 00277 00278 ================================================================================ 00279 MSG: sensor_msgs/CameraInfo 00280 # This message defines meta information for a camera. It should be in a 00281 # camera namespace on topic "camera_info" and accompanied by up to five 00282 # image topics named: 00283 # 00284 # image_raw - raw data from the camera driver, possibly Bayer encoded 00285 # image - monochrome, distorted 00286 # image_color - color, distorted 00287 # image_rect - monochrome, rectified 00288 # image_rect_color - color, rectified 00289 # 00290 # The image_pipeline contains packages (image_proc, stereo_image_proc) 00291 # for producing the four processed image topics from image_raw and 00292 # camera_info. The meaning of the camera parameters are described in 00293 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. 00294 # 00295 # The image_geometry package provides a user-friendly interface to 00296 # common operations using this meta information. If you want to, e.g., 00297 # project a 3d point into image coordinates, we strongly recommend 00298 # using image_geometry. 00299 # 00300 # If the camera is uncalibrated, the matrices D, K, R, P should be left 00301 # zeroed out. In particular, clients may assume that K[0] == 0.0 00302 # indicates an uncalibrated camera. 00303 00304 ####################################################################### 00305 # Image acquisition info # 00306 ####################################################################### 00307 00308 # Time of image acquisition, camera coordinate frame ID 00309 Header header # Header timestamp should be acquisition time of image 00310 # Header frame_id should be optical frame of camera 00311 # origin of frame should be optical center of camera 00312 # +x should point to the right in the image 00313 # +y should point down in the image 00314 # +z should point into the plane of the image 00315 00316 00317 ####################################################################### 00318 # Calibration Parameters # 00319 ####################################################################### 00320 # These are fixed during camera calibration. Their values will be the # 00321 # same in all messages until the camera is recalibrated. Note that # 00322 # self-calibrating systems may "recalibrate" frequently. # 00323 # # 00324 # The internal parameters can be used to warp a raw (distorted) image # 00325 # to: # 00326 # 1. An undistorted image (requires D and K) # 00327 # 2. A rectified image (requires D, K, R) # 00328 # The projection matrix P projects 3D points into the rectified image.# 00329 ####################################################################### 00330 00331 # The image dimensions with which the camera was calibrated. Normally 00332 # this will be the full camera resolution in pixels. 00333 uint32 height 00334 uint32 width 00335 00336 # The distortion model used. Supported models are listed in 00337 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a 00338 # simple model of radial and tangential distortion - is sufficent. 00339 string distortion_model 00340 00341 # The distortion parameters, size depending on the distortion model. 00342 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). 00343 float64[] D 00344 00345 # Intrinsic camera matrix for the raw (distorted) images. 00346 # [fx 0 cx] 00347 # K = [ 0 fy cy] 00348 # [ 0 0 1] 00349 # Projects 3D points in the camera coordinate frame to 2D pixel 00350 # coordinates using the focal lengths (fx, fy) and principal point 00351 # (cx, cy). 00352 float64[9] K # 3x3 row-major matrix 00353 00354 # Rectification matrix (stereo cameras only) 00355 # A rotation matrix aligning the camera coordinate system to the ideal 00356 # stereo image plane so that epipolar lines in both stereo images are 00357 # parallel. 00358 float64[9] R # 3x3 row-major matrix 00359 00360 # Projection/camera matrix 00361 # [fx' 0 cx' Tx] 00362 # P = [ 0 fy' cy' Ty] 00363 # [ 0 0 1 0] 00364 # By convention, this matrix specifies the intrinsic (camera) matrix 00365 # of the processed (rectified) image. That is, the left 3x3 portion 00366 # is the normal camera intrinsic matrix for the rectified image. 00367 # It projects 3D points in the camera coordinate frame to 2D pixel 00368 # coordinates using the focal lengths (fx', fy') and principal point 00369 # (cx', cy') - these may differ from the values in K. 00370 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will 00371 # also have R = the identity and P[1:3,1:3] = K. 00372 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the 00373 # position of the optical center of the second camera in the first 00374 # camera's frame. We assume Tz = 0 so both cameras are in the same 00375 # stereo image plane. The first camera always has Tx = Ty = 0. For 00376 # the right (second) camera of a horizontal stereo pair, Ty = 0 and 00377 # Tx = -fx' * B, where B is the baseline between the cameras. 00378 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto 00379 # the rectified image is given by: 00380 # [u v w]' = P * [X Y Z 1]' 00381 # x = u / w 00382 # y = v / w 00383 # This holds for both images of a stereo pair. 00384 float64[12] P # 3x4 row-major matrix 00385 00386 00387 ####################################################################### 00388 # Operational Parameters # 00389 ####################################################################### 00390 # These define the image region actually captured by the camera # 00391 # driver. Although they affect the geometry of the output image, they # 00392 # may be changed freely without recalibrating the camera. # 00393 ####################################################################### 00394 00395 # Binning refers here to any camera setting which combines rectangular 00396 # neighborhoods of pixels into larger "super-pixels." It reduces the 00397 # resolution of the output image to 00398 # (width / binning_x) x (height / binning_y). 00399 # The default values binning_x = binning_y = 0 is considered the same 00400 # as binning_x = binning_y = 1 (no subsampling). 00401 uint32 binning_x 00402 uint32 binning_y 00403 00404 # Region of interest (subwindow of full camera resolution), given in 00405 # full resolution (unbinned) image coordinates. A particular ROI 00406 # always denotes the same window of pixels on the camera sensor, 00407 # regardless of binning settings. 00408 # The default setting of roi (all values 0) is considered the same as 00409 # full resolution (roi.width = width, roi.height = height). 00410 RegionOfInterest roi 00411 00412 ================================================================================ 00413 MSG: sensor_msgs/RegionOfInterest 00414 # This message is used to specify a region of interest within an image. 00415 # 00416 # When used to specify the ROI setting of the camera when the image was 00417 # taken, the height and width fields should either match the height and 00418 # width fields for the associated image; or height = width = 0 00419 # indicates that the full resolution image was captured. 00420 00421 uint32 x_offset # Leftmost pixel of the ROI 00422 # (0 if the ROI includes the left edge of the image) 00423 uint32 y_offset # Topmost pixel of the ROI 00424 # (0 if the ROI includes the top edge of the image) 00425 uint32 height # Height of ROI 00426 uint32 width # Width of ROI 00427 00428 # True if a distinct rectified ROI should be calculated from the "raw" 00429 # ROI in this message. Typically this should be False if the full image 00430 # is captured (ROI not used), and True if a subwindow is captured (ROI 00431 # used). 00432 bool do_rectify 00433 00434 ================================================================================ 00435 MSG: geometry_msgs/Vector3 00436 # This represents a vector in free space. 00437 00438 float64 x 00439 float64 y 00440 float64 z 00441 ================================================================================ 00442 MSG: object_manipulation_msgs/Grasp 00443 00444 # The internal posture of the hand for the pre-grasp 00445 # only positions are used 00446 sensor_msgs/JointState pre_grasp_posture 00447 00448 # The internal posture of the hand for the grasp 00449 # positions and efforts are used 00450 sensor_msgs/JointState grasp_posture 00451 00452 # The position of the end-effector for the grasp relative to a reference frame 00453 # (that is always specified elsewhere, not in this message) 00454 geometry_msgs/Pose grasp_pose 00455 00456 # The estimated probability of success for this grasp 00457 float64 success_probability 00458 00459 # Debug flag to indicate that this grasp would be the best in its cluster 00460 bool cluster_rep 00461 00462 # how far the pre-grasp should ideally be away from the grasp 00463 float32 desired_approach_distance 00464 00465 # how much distance between pre-grasp and grasp must actually be feasible 00466 # for the grasp not to be rejected 00467 float32 min_approach_distance 00468 00469 # an optional list of obstacles that we have semantic information about 00470 # and that we expect might move in the course of executing this grasp 00471 # the grasp planner is expected to make sure they move in an OK way; during 00472 # execution, grasp executors will not check for collisions against these objects 00473 GraspableObject[] moved_obstacles 00474 00475 ================================================================================ 00476 MSG: sensor_msgs/JointState 00477 # This is a message that holds data to describe the state of a set of torque controlled joints. 00478 # 00479 # The state of each joint (revolute or prismatic) is defined by: 00480 # * the position of the joint (rad or m), 00481 # * the velocity of the joint (rad/s or m/s) and 00482 # * the effort that is applied in the joint (Nm or N). 00483 # 00484 # Each joint is uniquely identified by its name 00485 # The header specifies the time at which the joint states were recorded. All the joint states 00486 # in one message have to be recorded at the same time. 00487 # 00488 # This message consists of a multiple arrays, one for each part of the joint state. 00489 # The goal is to make each of the fields optional. When e.g. your joints have no 00490 # effort associated with them, you can leave the effort array empty. 00491 # 00492 # All arrays in this message should have the same size, or be empty. 00493 # This is the only way to uniquely associate the joint name with the correct 00494 # states. 00495 00496 00497 Header header 00498 00499 string[] name 00500 float64[] position 00501 float64[] velocity 00502 float64[] effort 00503 00504 """ 00505 __slots__ = ['arm_name','gripper_pose','gripper_opening','object','grasp'] 00506 _slot_types = ['string','geometry_msgs/PoseStamped','float32','object_manipulation_msgs/GraspableObject','object_manipulation_msgs/Grasp'] 00507 00508 def __init__(self, *args, **kwds): 00509 """ 00510 Constructor. Any message fields that are implicitly/explicitly 00511 set to None will be assigned a default value. The recommend 00512 use is keyword arguments as this is more robust to future message 00513 changes. You cannot mix in-order arguments and keyword arguments. 00514 00515 The available fields are: 00516 arm_name,gripper_pose,gripper_opening,object,grasp 00517 00518 @param args: complete set of field values, in .msg order 00519 @param kwds: use keyword arguments corresponding to message field names 00520 to set specific fields. 00521 """ 00522 if args or kwds: 00523 super(GetGripperPoseGoal, self).__init__(*args, **kwds) 00524 #message fields cannot be None, assign default values for those that are 00525 if self.arm_name is None: 00526 self.arm_name = '' 00527 if self.gripper_pose is None: 00528 self.gripper_pose = geometry_msgs.msg.PoseStamped() 00529 if self.gripper_opening is None: 00530 self.gripper_opening = 0. 00531 if self.object is None: 00532 self.object = object_manipulation_msgs.msg.GraspableObject() 00533 if self.grasp is None: 00534 self.grasp = object_manipulation_msgs.msg.Grasp() 00535 else: 00536 self.arm_name = '' 00537 self.gripper_pose = geometry_msgs.msg.PoseStamped() 00538 self.gripper_opening = 0. 00539 self.object = object_manipulation_msgs.msg.GraspableObject() 00540 self.grasp = object_manipulation_msgs.msg.Grasp() 00541 00542 def _get_types(self): 00543 """ 00544 internal API method 00545 """ 00546 return self._slot_types 00547 00548 def serialize(self, buff): 00549 """ 00550 serialize message into buffer 00551 @param buff: buffer 00552 @type buff: StringIO 00553 """ 00554 try: 00555 _x = self.arm_name 00556 length = len(_x) 00557 buff.write(struct.pack('<I%ss'%length, length, _x)) 00558 _x = self 00559 buff.write(_struct_3I.pack(_x.gripper_pose.header.seq, _x.gripper_pose.header.stamp.secs, _x.gripper_pose.header.stamp.nsecs)) 00560 _x = self.gripper_pose.header.frame_id 00561 length = len(_x) 00562 buff.write(struct.pack('<I%ss'%length, length, _x)) 00563 _x = self 00564 buff.write(_struct_7df.pack(_x.gripper_pose.pose.position.x, _x.gripper_pose.pose.position.y, _x.gripper_pose.pose.position.z, _x.gripper_pose.pose.orientation.x, _x.gripper_pose.pose.orientation.y, _x.gripper_pose.pose.orientation.z, _x.gripper_pose.pose.orientation.w, _x.gripper_opening)) 00565 _x = self.object.reference_frame_id 00566 length = len(_x) 00567 buff.write(struct.pack('<I%ss'%length, length, _x)) 00568 length = len(self.object.potential_models) 00569 buff.write(_struct_I.pack(length)) 00570 for val1 in self.object.potential_models: 00571 buff.write(_struct_i.pack(val1.model_id)) 00572 _v1 = val1.pose 00573 _v2 = _v1.header 00574 buff.write(_struct_I.pack(_v2.seq)) 00575 _v3 = _v2.stamp 00576 _x = _v3 00577 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00578 _x = _v2.frame_id 00579 length = len(_x) 00580 buff.write(struct.pack('<I%ss'%length, length, _x)) 00581 _v4 = _v1.pose 00582 _v5 = _v4.position 00583 _x = _v5 00584 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00585 _v6 = _v4.orientation 00586 _x = _v6 00587 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00588 buff.write(_struct_f.pack(val1.confidence)) 00589 _x = val1.detector_name 00590 length = len(_x) 00591 buff.write(struct.pack('<I%ss'%length, length, _x)) 00592 _x = self 00593 buff.write(_struct_3I.pack(_x.object.cluster.header.seq, _x.object.cluster.header.stamp.secs, _x.object.cluster.header.stamp.nsecs)) 00594 _x = self.object.cluster.header.frame_id 00595 length = len(_x) 00596 buff.write(struct.pack('<I%ss'%length, length, _x)) 00597 length = len(self.object.cluster.points) 00598 buff.write(_struct_I.pack(length)) 00599 for val1 in self.object.cluster.points: 00600 _x = val1 00601 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00602 length = len(self.object.cluster.channels) 00603 buff.write(_struct_I.pack(length)) 00604 for val1 in self.object.cluster.channels: 00605 _x = val1.name 00606 length = len(_x) 00607 buff.write(struct.pack('<I%ss'%length, length, _x)) 00608 length = len(val1.values) 00609 buff.write(_struct_I.pack(length)) 00610 pattern = '<%sf'%length 00611 buff.write(struct.pack(pattern, *val1.values)) 00612 _x = self 00613 buff.write(_struct_3I.pack(_x.object.region.cloud.header.seq, _x.object.region.cloud.header.stamp.secs, _x.object.region.cloud.header.stamp.nsecs)) 00614 _x = self.object.region.cloud.header.frame_id 00615 length = len(_x) 00616 buff.write(struct.pack('<I%ss'%length, length, _x)) 00617 _x = self 00618 buff.write(_struct_2I.pack(_x.object.region.cloud.height, _x.object.region.cloud.width)) 00619 length = len(self.object.region.cloud.fields) 00620 buff.write(_struct_I.pack(length)) 00621 for val1 in self.object.region.cloud.fields: 00622 _x = val1.name 00623 length = len(_x) 00624 buff.write(struct.pack('<I%ss'%length, length, _x)) 00625 _x = val1 00626 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 00627 _x = self 00628 buff.write(_struct_B2I.pack(_x.object.region.cloud.is_bigendian, _x.object.region.cloud.point_step, _x.object.region.cloud.row_step)) 00629 _x = self.object.region.cloud.data 00630 length = len(_x) 00631 # - if encoded as a list instead, serialize as bytes instead of string 00632 if type(_x) in [list, tuple]: 00633 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00634 else: 00635 buff.write(struct.pack('<I%ss'%length, length, _x)) 00636 buff.write(_struct_B.pack(self.object.region.cloud.is_dense)) 00637 length = len(self.object.region.mask) 00638 buff.write(_struct_I.pack(length)) 00639 pattern = '<%si'%length 00640 buff.write(struct.pack(pattern, *self.object.region.mask)) 00641 _x = self 00642 buff.write(_struct_3I.pack(_x.object.region.image.header.seq, _x.object.region.image.header.stamp.secs, _x.object.region.image.header.stamp.nsecs)) 00643 _x = self.object.region.image.header.frame_id 00644 length = len(_x) 00645 buff.write(struct.pack('<I%ss'%length, length, _x)) 00646 _x = self 00647 buff.write(_struct_2I.pack(_x.object.region.image.height, _x.object.region.image.width)) 00648 _x = self.object.region.image.encoding 00649 length = len(_x) 00650 buff.write(struct.pack('<I%ss'%length, length, _x)) 00651 _x = self 00652 buff.write(_struct_BI.pack(_x.object.region.image.is_bigendian, _x.object.region.image.step)) 00653 _x = self.object.region.image.data 00654 length = len(_x) 00655 # - if encoded as a list instead, serialize as bytes instead of string 00656 if type(_x) in [list, tuple]: 00657 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00658 else: 00659 buff.write(struct.pack('<I%ss'%length, length, _x)) 00660 _x = self 00661 buff.write(_struct_3I.pack(_x.object.region.disparity_image.header.seq, _x.object.region.disparity_image.header.stamp.secs, _x.object.region.disparity_image.header.stamp.nsecs)) 00662 _x = self.object.region.disparity_image.header.frame_id 00663 length = len(_x) 00664 buff.write(struct.pack('<I%ss'%length, length, _x)) 00665 _x = self 00666 buff.write(_struct_2I.pack(_x.object.region.disparity_image.height, _x.object.region.disparity_image.width)) 00667 _x = self.object.region.disparity_image.encoding 00668 length = len(_x) 00669 buff.write(struct.pack('<I%ss'%length, length, _x)) 00670 _x = self 00671 buff.write(_struct_BI.pack(_x.object.region.disparity_image.is_bigendian, _x.object.region.disparity_image.step)) 00672 _x = self.object.region.disparity_image.data 00673 length = len(_x) 00674 # - if encoded as a list instead, serialize as bytes instead of string 00675 if type(_x) in [list, tuple]: 00676 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00677 else: 00678 buff.write(struct.pack('<I%ss'%length, length, _x)) 00679 _x = self 00680 buff.write(_struct_3I.pack(_x.object.region.cam_info.header.seq, _x.object.region.cam_info.header.stamp.secs, _x.object.region.cam_info.header.stamp.nsecs)) 00681 _x = self.object.region.cam_info.header.frame_id 00682 length = len(_x) 00683 buff.write(struct.pack('<I%ss'%length, length, _x)) 00684 _x = self 00685 buff.write(_struct_2I.pack(_x.object.region.cam_info.height, _x.object.region.cam_info.width)) 00686 _x = self.object.region.cam_info.distortion_model 00687 length = len(_x) 00688 buff.write(struct.pack('<I%ss'%length, length, _x)) 00689 length = len(self.object.region.cam_info.D) 00690 buff.write(_struct_I.pack(length)) 00691 pattern = '<%sd'%length 00692 buff.write(struct.pack(pattern, *self.object.region.cam_info.D)) 00693 buff.write(_struct_9d.pack(*self.object.region.cam_info.K)) 00694 buff.write(_struct_9d.pack(*self.object.region.cam_info.R)) 00695 buff.write(_struct_12d.pack(*self.object.region.cam_info.P)) 00696 _x = self 00697 buff.write(_struct_6IB3I.pack(_x.object.region.cam_info.binning_x, _x.object.region.cam_info.binning_y, _x.object.region.cam_info.roi.x_offset, _x.object.region.cam_info.roi.y_offset, _x.object.region.cam_info.roi.height, _x.object.region.cam_info.roi.width, _x.object.region.cam_info.roi.do_rectify, _x.object.region.roi_box_pose.header.seq, _x.object.region.roi_box_pose.header.stamp.secs, _x.object.region.roi_box_pose.header.stamp.nsecs)) 00698 _x = self.object.region.roi_box_pose.header.frame_id 00699 length = len(_x) 00700 buff.write(struct.pack('<I%ss'%length, length, _x)) 00701 _x = self 00702 buff.write(_struct_10d.pack(_x.object.region.roi_box_pose.pose.position.x, _x.object.region.roi_box_pose.pose.position.y, _x.object.region.roi_box_pose.pose.position.z, _x.object.region.roi_box_pose.pose.orientation.x, _x.object.region.roi_box_pose.pose.orientation.y, _x.object.region.roi_box_pose.pose.orientation.z, _x.object.region.roi_box_pose.pose.orientation.w, _x.object.region.roi_box_dims.x, _x.object.region.roi_box_dims.y, _x.object.region.roi_box_dims.z)) 00703 _x = self.object.collision_name 00704 length = len(_x) 00705 buff.write(struct.pack('<I%ss'%length, length, _x)) 00706 _x = self 00707 buff.write(_struct_3I.pack(_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs)) 00708 _x = self.grasp.pre_grasp_posture.header.frame_id 00709 length = len(_x) 00710 buff.write(struct.pack('<I%ss'%length, length, _x)) 00711 length = len(self.grasp.pre_grasp_posture.name) 00712 buff.write(_struct_I.pack(length)) 00713 for val1 in self.grasp.pre_grasp_posture.name: 00714 length = len(val1) 00715 buff.write(struct.pack('<I%ss'%length, length, val1)) 00716 length = len(self.grasp.pre_grasp_posture.position) 00717 buff.write(_struct_I.pack(length)) 00718 pattern = '<%sd'%length 00719 buff.write(struct.pack(pattern, *self.grasp.pre_grasp_posture.position)) 00720 length = len(self.grasp.pre_grasp_posture.velocity) 00721 buff.write(_struct_I.pack(length)) 00722 pattern = '<%sd'%length 00723 buff.write(struct.pack(pattern, *self.grasp.pre_grasp_posture.velocity)) 00724 length = len(self.grasp.pre_grasp_posture.effort) 00725 buff.write(_struct_I.pack(length)) 00726 pattern = '<%sd'%length 00727 buff.write(struct.pack(pattern, *self.grasp.pre_grasp_posture.effort)) 00728 _x = self 00729 buff.write(_struct_3I.pack(_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs)) 00730 _x = self.grasp.grasp_posture.header.frame_id 00731 length = len(_x) 00732 buff.write(struct.pack('<I%ss'%length, length, _x)) 00733 length = len(self.grasp.grasp_posture.name) 00734 buff.write(_struct_I.pack(length)) 00735 for val1 in self.grasp.grasp_posture.name: 00736 length = len(val1) 00737 buff.write(struct.pack('<I%ss'%length, length, val1)) 00738 length = len(self.grasp.grasp_posture.position) 00739 buff.write(_struct_I.pack(length)) 00740 pattern = '<%sd'%length 00741 buff.write(struct.pack(pattern, *self.grasp.grasp_posture.position)) 00742 length = len(self.grasp.grasp_posture.velocity) 00743 buff.write(_struct_I.pack(length)) 00744 pattern = '<%sd'%length 00745 buff.write(struct.pack(pattern, *self.grasp.grasp_posture.velocity)) 00746 length = len(self.grasp.grasp_posture.effort) 00747 buff.write(_struct_I.pack(length)) 00748 pattern = '<%sd'%length 00749 buff.write(struct.pack(pattern, *self.grasp.grasp_posture.effort)) 00750 _x = self 00751 buff.write(_struct_8dB2f.pack(_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance)) 00752 length = len(self.grasp.moved_obstacles) 00753 buff.write(_struct_I.pack(length)) 00754 for val1 in self.grasp.moved_obstacles: 00755 _x = val1.reference_frame_id 00756 length = len(_x) 00757 buff.write(struct.pack('<I%ss'%length, length, _x)) 00758 length = len(val1.potential_models) 00759 buff.write(_struct_I.pack(length)) 00760 for val2 in val1.potential_models: 00761 buff.write(_struct_i.pack(val2.model_id)) 00762 _v7 = val2.pose 00763 _v8 = _v7.header 00764 buff.write(_struct_I.pack(_v8.seq)) 00765 _v9 = _v8.stamp 00766 _x = _v9 00767 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00768 _x = _v8.frame_id 00769 length = len(_x) 00770 buff.write(struct.pack('<I%ss'%length, length, _x)) 00771 _v10 = _v7.pose 00772 _v11 = _v10.position 00773 _x = _v11 00774 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00775 _v12 = _v10.orientation 00776 _x = _v12 00777 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00778 buff.write(_struct_f.pack(val2.confidence)) 00779 _x = val2.detector_name 00780 length = len(_x) 00781 buff.write(struct.pack('<I%ss'%length, length, _x)) 00782 _v13 = val1.cluster 00783 _v14 = _v13.header 00784 buff.write(_struct_I.pack(_v14.seq)) 00785 _v15 = _v14.stamp 00786 _x = _v15 00787 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00788 _x = _v14.frame_id 00789 length = len(_x) 00790 buff.write(struct.pack('<I%ss'%length, length, _x)) 00791 length = len(_v13.points) 00792 buff.write(_struct_I.pack(length)) 00793 for val3 in _v13.points: 00794 _x = val3 00795 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00796 length = len(_v13.channels) 00797 buff.write(_struct_I.pack(length)) 00798 for val3 in _v13.channels: 00799 _x = val3.name 00800 length = len(_x) 00801 buff.write(struct.pack('<I%ss'%length, length, _x)) 00802 length = len(val3.values) 00803 buff.write(_struct_I.pack(length)) 00804 pattern = '<%sf'%length 00805 buff.write(struct.pack(pattern, *val3.values)) 00806 _v16 = val1.region 00807 _v17 = _v16.cloud 00808 _v18 = _v17.header 00809 buff.write(_struct_I.pack(_v18.seq)) 00810 _v19 = _v18.stamp 00811 _x = _v19 00812 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00813 _x = _v18.frame_id 00814 length = len(_x) 00815 buff.write(struct.pack('<I%ss'%length, length, _x)) 00816 _x = _v17 00817 buff.write(_struct_2I.pack(_x.height, _x.width)) 00818 length = len(_v17.fields) 00819 buff.write(_struct_I.pack(length)) 00820 for val4 in _v17.fields: 00821 _x = val4.name 00822 length = len(_x) 00823 buff.write(struct.pack('<I%ss'%length, length, _x)) 00824 _x = val4 00825 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 00826 _x = _v17 00827 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step)) 00828 _x = _v17.data 00829 length = len(_x) 00830 # - if encoded as a list instead, serialize as bytes instead of string 00831 if type(_x) in [list, tuple]: 00832 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00833 else: 00834 buff.write(struct.pack('<I%ss'%length, length, _x)) 00835 buff.write(_struct_B.pack(_v17.is_dense)) 00836 length = len(_v16.mask) 00837 buff.write(_struct_I.pack(length)) 00838 pattern = '<%si'%length 00839 buff.write(struct.pack(pattern, *_v16.mask)) 00840 _v20 = _v16.image 00841 _v21 = _v20.header 00842 buff.write(_struct_I.pack(_v21.seq)) 00843 _v22 = _v21.stamp 00844 _x = _v22 00845 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00846 _x = _v21.frame_id 00847 length = len(_x) 00848 buff.write(struct.pack('<I%ss'%length, length, _x)) 00849 _x = _v20 00850 buff.write(_struct_2I.pack(_x.height, _x.width)) 00851 _x = _v20.encoding 00852 length = len(_x) 00853 buff.write(struct.pack('<I%ss'%length, length, _x)) 00854 _x = _v20 00855 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 00856 _x = _v20.data 00857 length = len(_x) 00858 # - if encoded as a list instead, serialize as bytes instead of string 00859 if type(_x) in [list, tuple]: 00860 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00861 else: 00862 buff.write(struct.pack('<I%ss'%length, length, _x)) 00863 _v23 = _v16.disparity_image 00864 _v24 = _v23.header 00865 buff.write(_struct_I.pack(_v24.seq)) 00866 _v25 = _v24.stamp 00867 _x = _v25 00868 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00869 _x = _v24.frame_id 00870 length = len(_x) 00871 buff.write(struct.pack('<I%ss'%length, length, _x)) 00872 _x = _v23 00873 buff.write(_struct_2I.pack(_x.height, _x.width)) 00874 _x = _v23.encoding 00875 length = len(_x) 00876 buff.write(struct.pack('<I%ss'%length, length, _x)) 00877 _x = _v23 00878 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 00879 _x = _v23.data 00880 length = len(_x) 00881 # - if encoded as a list instead, serialize as bytes instead of string 00882 if type(_x) in [list, tuple]: 00883 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00884 else: 00885 buff.write(struct.pack('<I%ss'%length, length, _x)) 00886 _v26 = _v16.cam_info 00887 _v27 = _v26.header 00888 buff.write(_struct_I.pack(_v27.seq)) 00889 _v28 = _v27.stamp 00890 _x = _v28 00891 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00892 _x = _v27.frame_id 00893 length = len(_x) 00894 buff.write(struct.pack('<I%ss'%length, length, _x)) 00895 _x = _v26 00896 buff.write(_struct_2I.pack(_x.height, _x.width)) 00897 _x = _v26.distortion_model 00898 length = len(_x) 00899 buff.write(struct.pack('<I%ss'%length, length, _x)) 00900 length = len(_v26.D) 00901 buff.write(_struct_I.pack(length)) 00902 pattern = '<%sd'%length 00903 buff.write(struct.pack(pattern, *_v26.D)) 00904 buff.write(_struct_9d.pack(*_v26.K)) 00905 buff.write(_struct_9d.pack(*_v26.R)) 00906 buff.write(_struct_12d.pack(*_v26.P)) 00907 _x = _v26 00908 buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y)) 00909 _v29 = _v26.roi 00910 _x = _v29 00911 buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify)) 00912 _v30 = _v16.roi_box_pose 00913 _v31 = _v30.header 00914 buff.write(_struct_I.pack(_v31.seq)) 00915 _v32 = _v31.stamp 00916 _x = _v32 00917 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00918 _x = _v31.frame_id 00919 length = len(_x) 00920 buff.write(struct.pack('<I%ss'%length, length, _x)) 00921 _v33 = _v30.pose 00922 _v34 = _v33.position 00923 _x = _v34 00924 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00925 _v35 = _v33.orientation 00926 _x = _v35 00927 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00928 _v36 = _v16.roi_box_dims 00929 _x = _v36 00930 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00931 _x = val1.collision_name 00932 length = len(_x) 00933 buff.write(struct.pack('<I%ss'%length, length, _x)) 00934 except struct.error as se: self._check_types(se) 00935 except TypeError as te: self._check_types(te) 00936 00937 def deserialize(self, str): 00938 """ 00939 unpack serialized message in str into this message instance 00940 @param str: byte array of serialized message 00941 @type str: str 00942 """ 00943 try: 00944 if self.gripper_pose is None: 00945 self.gripper_pose = geometry_msgs.msg.PoseStamped() 00946 if self.object is None: 00947 self.object = object_manipulation_msgs.msg.GraspableObject() 00948 if self.grasp is None: 00949 self.grasp = object_manipulation_msgs.msg.Grasp() 00950 end = 0 00951 start = end 00952 end += 4 00953 (length,) = _struct_I.unpack(str[start:end]) 00954 start = end 00955 end += length 00956 self.arm_name = str[start:end] 00957 _x = self 00958 start = end 00959 end += 12 00960 (_x.gripper_pose.header.seq, _x.gripper_pose.header.stamp.secs, _x.gripper_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00961 start = end 00962 end += 4 00963 (length,) = _struct_I.unpack(str[start:end]) 00964 start = end 00965 end += length 00966 self.gripper_pose.header.frame_id = str[start:end] 00967 _x = self 00968 start = end 00969 end += 60 00970 (_x.gripper_pose.pose.position.x, _x.gripper_pose.pose.position.y, _x.gripper_pose.pose.position.z, _x.gripper_pose.pose.orientation.x, _x.gripper_pose.pose.orientation.y, _x.gripper_pose.pose.orientation.z, _x.gripper_pose.pose.orientation.w, _x.gripper_opening,) = _struct_7df.unpack(str[start:end]) 00971 start = end 00972 end += 4 00973 (length,) = _struct_I.unpack(str[start:end]) 00974 start = end 00975 end += length 00976 self.object.reference_frame_id = str[start:end] 00977 start = end 00978 end += 4 00979 (length,) = _struct_I.unpack(str[start:end]) 00980 self.object.potential_models = [] 00981 for i in range(0, length): 00982 val1 = household_objects_database_msgs.msg.DatabaseModelPose() 00983 start = end 00984 end += 4 00985 (val1.model_id,) = _struct_i.unpack(str[start:end]) 00986 _v37 = val1.pose 00987 _v38 = _v37.header 00988 start = end 00989 end += 4 00990 (_v38.seq,) = _struct_I.unpack(str[start:end]) 00991 _v39 = _v38.stamp 00992 _x = _v39 00993 start = end 00994 end += 8 00995 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00996 start = end 00997 end += 4 00998 (length,) = _struct_I.unpack(str[start:end]) 00999 start = end 01000 end += length 01001 _v38.frame_id = str[start:end] 01002 _v40 = _v37.pose 01003 _v41 = _v40.position 01004 _x = _v41 01005 start = end 01006 end += 24 01007 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01008 _v42 = _v40.orientation 01009 _x = _v42 01010 start = end 01011 end += 32 01012 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01013 start = end 01014 end += 4 01015 (val1.confidence,) = _struct_f.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 val1.detector_name = str[start:end] 01022 self.object.potential_models.append(val1) 01023 _x = self 01024 start = end 01025 end += 12 01026 (_x.object.cluster.header.seq, _x.object.cluster.header.stamp.secs, _x.object.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01027 start = end 01028 end += 4 01029 (length,) = _struct_I.unpack(str[start:end]) 01030 start = end 01031 end += length 01032 self.object.cluster.header.frame_id = str[start:end] 01033 start = end 01034 end += 4 01035 (length,) = _struct_I.unpack(str[start:end]) 01036 self.object.cluster.points = [] 01037 for i in range(0, length): 01038 val1 = geometry_msgs.msg.Point32() 01039 _x = val1 01040 start = end 01041 end += 12 01042 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01043 self.object.cluster.points.append(val1) 01044 start = end 01045 end += 4 01046 (length,) = _struct_I.unpack(str[start:end]) 01047 self.object.cluster.channels = [] 01048 for i in range(0, length): 01049 val1 = sensor_msgs.msg.ChannelFloat32() 01050 start = end 01051 end += 4 01052 (length,) = _struct_I.unpack(str[start:end]) 01053 start = end 01054 end += length 01055 val1.name = str[start:end] 01056 start = end 01057 end += 4 01058 (length,) = _struct_I.unpack(str[start:end]) 01059 pattern = '<%sf'%length 01060 start = end 01061 end += struct.calcsize(pattern) 01062 val1.values = struct.unpack(pattern, str[start:end]) 01063 self.object.cluster.channels.append(val1) 01064 _x = self 01065 start = end 01066 end += 12 01067 (_x.object.region.cloud.header.seq, _x.object.region.cloud.header.stamp.secs, _x.object.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01068 start = end 01069 end += 4 01070 (length,) = _struct_I.unpack(str[start:end]) 01071 start = end 01072 end += length 01073 self.object.region.cloud.header.frame_id = str[start:end] 01074 _x = self 01075 start = end 01076 end += 8 01077 (_x.object.region.cloud.height, _x.object.region.cloud.width,) = _struct_2I.unpack(str[start:end]) 01078 start = end 01079 end += 4 01080 (length,) = _struct_I.unpack(str[start:end]) 01081 self.object.region.cloud.fields = [] 01082 for i in range(0, length): 01083 val1 = sensor_msgs.msg.PointField() 01084 start = end 01085 end += 4 01086 (length,) = _struct_I.unpack(str[start:end]) 01087 start = end 01088 end += length 01089 val1.name = str[start:end] 01090 _x = val1 01091 start = end 01092 end += 9 01093 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 01094 self.object.region.cloud.fields.append(val1) 01095 _x = self 01096 start = end 01097 end += 9 01098 (_x.object.region.cloud.is_bigendian, _x.object.region.cloud.point_step, _x.object.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end]) 01099 self.object.region.cloud.is_bigendian = bool(self.object.region.cloud.is_bigendian) 01100 start = end 01101 end += 4 01102 (length,) = _struct_I.unpack(str[start:end]) 01103 start = end 01104 end += length 01105 self.object.region.cloud.data = str[start:end] 01106 start = end 01107 end += 1 01108 (self.object.region.cloud.is_dense,) = _struct_B.unpack(str[start:end]) 01109 self.object.region.cloud.is_dense = bool(self.object.region.cloud.is_dense) 01110 start = end 01111 end += 4 01112 (length,) = _struct_I.unpack(str[start:end]) 01113 pattern = '<%si'%length 01114 start = end 01115 end += struct.calcsize(pattern) 01116 self.object.region.mask = struct.unpack(pattern, str[start:end]) 01117 _x = self 01118 start = end 01119 end += 12 01120 (_x.object.region.image.header.seq, _x.object.region.image.header.stamp.secs, _x.object.region.image.header.stamp.nsecs,) = _struct_3I.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.object.region.image.header.frame_id = str[start:end] 01127 _x = self 01128 start = end 01129 end += 8 01130 (_x.object.region.image.height, _x.object.region.image.width,) = _struct_2I.unpack(str[start:end]) 01131 start = end 01132 end += 4 01133 (length,) = _struct_I.unpack(str[start:end]) 01134 start = end 01135 end += length 01136 self.object.region.image.encoding = str[start:end] 01137 _x = self 01138 start = end 01139 end += 5 01140 (_x.object.region.image.is_bigendian, _x.object.region.image.step,) = _struct_BI.unpack(str[start:end]) 01141 start = end 01142 end += 4 01143 (length,) = _struct_I.unpack(str[start:end]) 01144 start = end 01145 end += length 01146 self.object.region.image.data = str[start:end] 01147 _x = self 01148 start = end 01149 end += 12 01150 (_x.object.region.disparity_image.header.seq, _x.object.region.disparity_image.header.stamp.secs, _x.object.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01151 start = end 01152 end += 4 01153 (length,) = _struct_I.unpack(str[start:end]) 01154 start = end 01155 end += length 01156 self.object.region.disparity_image.header.frame_id = str[start:end] 01157 _x = self 01158 start = end 01159 end += 8 01160 (_x.object.region.disparity_image.height, _x.object.region.disparity_image.width,) = _struct_2I.unpack(str[start:end]) 01161 start = end 01162 end += 4 01163 (length,) = _struct_I.unpack(str[start:end]) 01164 start = end 01165 end += length 01166 self.object.region.disparity_image.encoding = str[start:end] 01167 _x = self 01168 start = end 01169 end += 5 01170 (_x.object.region.disparity_image.is_bigendian, _x.object.region.disparity_image.step,) = _struct_BI.unpack(str[start:end]) 01171 start = end 01172 end += 4 01173 (length,) = _struct_I.unpack(str[start:end]) 01174 start = end 01175 end += length 01176 self.object.region.disparity_image.data = str[start:end] 01177 _x = self 01178 start = end 01179 end += 12 01180 (_x.object.region.cam_info.header.seq, _x.object.region.cam_info.header.stamp.secs, _x.object.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01181 start = end 01182 end += 4 01183 (length,) = _struct_I.unpack(str[start:end]) 01184 start = end 01185 end += length 01186 self.object.region.cam_info.header.frame_id = str[start:end] 01187 _x = self 01188 start = end 01189 end += 8 01190 (_x.object.region.cam_info.height, _x.object.region.cam_info.width,) = _struct_2I.unpack(str[start:end]) 01191 start = end 01192 end += 4 01193 (length,) = _struct_I.unpack(str[start:end]) 01194 start = end 01195 end += length 01196 self.object.region.cam_info.distortion_model = str[start:end] 01197 start = end 01198 end += 4 01199 (length,) = _struct_I.unpack(str[start:end]) 01200 pattern = '<%sd'%length 01201 start = end 01202 end += struct.calcsize(pattern) 01203 self.object.region.cam_info.D = struct.unpack(pattern, str[start:end]) 01204 start = end 01205 end += 72 01206 self.object.region.cam_info.K = _struct_9d.unpack(str[start:end]) 01207 start = end 01208 end += 72 01209 self.object.region.cam_info.R = _struct_9d.unpack(str[start:end]) 01210 start = end 01211 end += 96 01212 self.object.region.cam_info.P = _struct_12d.unpack(str[start:end]) 01213 _x = self 01214 start = end 01215 end += 37 01216 (_x.object.region.cam_info.binning_x, _x.object.region.cam_info.binning_y, _x.object.region.cam_info.roi.x_offset, _x.object.region.cam_info.roi.y_offset, _x.object.region.cam_info.roi.height, _x.object.region.cam_info.roi.width, _x.object.region.cam_info.roi.do_rectify, _x.object.region.roi_box_pose.header.seq, _x.object.region.roi_box_pose.header.stamp.secs, _x.object.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end]) 01217 self.object.region.cam_info.roi.do_rectify = bool(self.object.region.cam_info.roi.do_rectify) 01218 start = end 01219 end += 4 01220 (length,) = _struct_I.unpack(str[start:end]) 01221 start = end 01222 end += length 01223 self.object.region.roi_box_pose.header.frame_id = str[start:end] 01224 _x = self 01225 start = end 01226 end += 80 01227 (_x.object.region.roi_box_pose.pose.position.x, _x.object.region.roi_box_pose.pose.position.y, _x.object.region.roi_box_pose.pose.position.z, _x.object.region.roi_box_pose.pose.orientation.x, _x.object.region.roi_box_pose.pose.orientation.y, _x.object.region.roi_box_pose.pose.orientation.z, _x.object.region.roi_box_pose.pose.orientation.w, _x.object.region.roi_box_dims.x, _x.object.region.roi_box_dims.y, _x.object.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end]) 01228 start = end 01229 end += 4 01230 (length,) = _struct_I.unpack(str[start:end]) 01231 start = end 01232 end += length 01233 self.object.collision_name = str[start:end] 01234 _x = self 01235 start = end 01236 end += 12 01237 (_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01238 start = end 01239 end += 4 01240 (length,) = _struct_I.unpack(str[start:end]) 01241 start = end 01242 end += length 01243 self.grasp.pre_grasp_posture.header.frame_id = str[start:end] 01244 start = end 01245 end += 4 01246 (length,) = _struct_I.unpack(str[start:end]) 01247 self.grasp.pre_grasp_posture.name = [] 01248 for i in range(0, length): 01249 start = end 01250 end += 4 01251 (length,) = _struct_I.unpack(str[start:end]) 01252 start = end 01253 end += length 01254 val1 = str[start:end] 01255 self.grasp.pre_grasp_posture.name.append(val1) 01256 start = end 01257 end += 4 01258 (length,) = _struct_I.unpack(str[start:end]) 01259 pattern = '<%sd'%length 01260 start = end 01261 end += struct.calcsize(pattern) 01262 self.grasp.pre_grasp_posture.position = struct.unpack(pattern, str[start:end]) 01263 start = end 01264 end += 4 01265 (length,) = _struct_I.unpack(str[start:end]) 01266 pattern = '<%sd'%length 01267 start = end 01268 end += struct.calcsize(pattern) 01269 self.grasp.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end]) 01270 start = end 01271 end += 4 01272 (length,) = _struct_I.unpack(str[start:end]) 01273 pattern = '<%sd'%length 01274 start = end 01275 end += struct.calcsize(pattern) 01276 self.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end]) 01277 _x = self 01278 start = end 01279 end += 12 01280 (_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01281 start = end 01282 end += 4 01283 (length,) = _struct_I.unpack(str[start:end]) 01284 start = end 01285 end += length 01286 self.grasp.grasp_posture.header.frame_id = str[start:end] 01287 start = end 01288 end += 4 01289 (length,) = _struct_I.unpack(str[start:end]) 01290 self.grasp.grasp_posture.name = [] 01291 for i in range(0, length): 01292 start = end 01293 end += 4 01294 (length,) = _struct_I.unpack(str[start:end]) 01295 start = end 01296 end += length 01297 val1 = str[start:end] 01298 self.grasp.grasp_posture.name.append(val1) 01299 start = end 01300 end += 4 01301 (length,) = _struct_I.unpack(str[start:end]) 01302 pattern = '<%sd'%length 01303 start = end 01304 end += struct.calcsize(pattern) 01305 self.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end]) 01306 start = end 01307 end += 4 01308 (length,) = _struct_I.unpack(str[start:end]) 01309 pattern = '<%sd'%length 01310 start = end 01311 end += struct.calcsize(pattern) 01312 self.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end]) 01313 start = end 01314 end += 4 01315 (length,) = _struct_I.unpack(str[start:end]) 01316 pattern = '<%sd'%length 01317 start = end 01318 end += struct.calcsize(pattern) 01319 self.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end]) 01320 _x = self 01321 start = end 01322 end += 73 01323 (_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end]) 01324 self.grasp.cluster_rep = bool(self.grasp.cluster_rep) 01325 start = end 01326 end += 4 01327 (length,) = _struct_I.unpack(str[start:end]) 01328 self.grasp.moved_obstacles = [] 01329 for i in range(0, length): 01330 val1 = object_manipulation_msgs.msg.GraspableObject() 01331 start = end 01332 end += 4 01333 (length,) = _struct_I.unpack(str[start:end]) 01334 start = end 01335 end += length 01336 val1.reference_frame_id = str[start:end] 01337 start = end 01338 end += 4 01339 (length,) = _struct_I.unpack(str[start:end]) 01340 val1.potential_models = [] 01341 for i in range(0, length): 01342 val2 = household_objects_database_msgs.msg.DatabaseModelPose() 01343 start = end 01344 end += 4 01345 (val2.model_id,) = _struct_i.unpack(str[start:end]) 01346 _v43 = val2.pose 01347 _v44 = _v43.header 01348 start = end 01349 end += 4 01350 (_v44.seq,) = _struct_I.unpack(str[start:end]) 01351 _v45 = _v44.stamp 01352 _x = _v45 01353 start = end 01354 end += 8 01355 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01356 start = end 01357 end += 4 01358 (length,) = _struct_I.unpack(str[start:end]) 01359 start = end 01360 end += length 01361 _v44.frame_id = str[start:end] 01362 _v46 = _v43.pose 01363 _v47 = _v46.position 01364 _x = _v47 01365 start = end 01366 end += 24 01367 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01368 _v48 = _v46.orientation 01369 _x = _v48 01370 start = end 01371 end += 32 01372 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01373 start = end 01374 end += 4 01375 (val2.confidence,) = _struct_f.unpack(str[start:end]) 01376 start = end 01377 end += 4 01378 (length,) = _struct_I.unpack(str[start:end]) 01379 start = end 01380 end += length 01381 val2.detector_name = str[start:end] 01382 val1.potential_models.append(val2) 01383 _v49 = val1.cluster 01384 _v50 = _v49.header 01385 start = end 01386 end += 4 01387 (_v50.seq,) = _struct_I.unpack(str[start:end]) 01388 _v51 = _v50.stamp 01389 _x = _v51 01390 start = end 01391 end += 8 01392 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01393 start = end 01394 end += 4 01395 (length,) = _struct_I.unpack(str[start:end]) 01396 start = end 01397 end += length 01398 _v50.frame_id = str[start:end] 01399 start = end 01400 end += 4 01401 (length,) = _struct_I.unpack(str[start:end]) 01402 _v49.points = [] 01403 for i in range(0, length): 01404 val3 = geometry_msgs.msg.Point32() 01405 _x = val3 01406 start = end 01407 end += 12 01408 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01409 _v49.points.append(val3) 01410 start = end 01411 end += 4 01412 (length,) = _struct_I.unpack(str[start:end]) 01413 _v49.channels = [] 01414 for i in range(0, length): 01415 val3 = sensor_msgs.msg.ChannelFloat32() 01416 start = end 01417 end += 4 01418 (length,) = _struct_I.unpack(str[start:end]) 01419 start = end 01420 end += length 01421 val3.name = str[start:end] 01422 start = end 01423 end += 4 01424 (length,) = _struct_I.unpack(str[start:end]) 01425 pattern = '<%sf'%length 01426 start = end 01427 end += struct.calcsize(pattern) 01428 val3.values = struct.unpack(pattern, str[start:end]) 01429 _v49.channels.append(val3) 01430 _v52 = val1.region 01431 _v53 = _v52.cloud 01432 _v54 = _v53.header 01433 start = end 01434 end += 4 01435 (_v54.seq,) = _struct_I.unpack(str[start:end]) 01436 _v55 = _v54.stamp 01437 _x = _v55 01438 start = end 01439 end += 8 01440 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01441 start = end 01442 end += 4 01443 (length,) = _struct_I.unpack(str[start:end]) 01444 start = end 01445 end += length 01446 _v54.frame_id = str[start:end] 01447 _x = _v53 01448 start = end 01449 end += 8 01450 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01451 start = end 01452 end += 4 01453 (length,) = _struct_I.unpack(str[start:end]) 01454 _v53.fields = [] 01455 for i in range(0, length): 01456 val4 = sensor_msgs.msg.PointField() 01457 start = end 01458 end += 4 01459 (length,) = _struct_I.unpack(str[start:end]) 01460 start = end 01461 end += length 01462 val4.name = str[start:end] 01463 _x = val4 01464 start = end 01465 end += 9 01466 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 01467 _v53.fields.append(val4) 01468 _x = _v53 01469 start = end 01470 end += 9 01471 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end]) 01472 _v53.is_bigendian = bool(_v53.is_bigendian) 01473 start = end 01474 end += 4 01475 (length,) = _struct_I.unpack(str[start:end]) 01476 start = end 01477 end += length 01478 _v53.data = str[start:end] 01479 start = end 01480 end += 1 01481 (_v53.is_dense,) = _struct_B.unpack(str[start:end]) 01482 _v53.is_dense = bool(_v53.is_dense) 01483 start = end 01484 end += 4 01485 (length,) = _struct_I.unpack(str[start:end]) 01486 pattern = '<%si'%length 01487 start = end 01488 end += struct.calcsize(pattern) 01489 _v52.mask = struct.unpack(pattern, str[start:end]) 01490 _v56 = _v52.image 01491 _v57 = _v56.header 01492 start = end 01493 end += 4 01494 (_v57.seq,) = _struct_I.unpack(str[start:end]) 01495 _v58 = _v57.stamp 01496 _x = _v58 01497 start = end 01498 end += 8 01499 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01500 start = end 01501 end += 4 01502 (length,) = _struct_I.unpack(str[start:end]) 01503 start = end 01504 end += length 01505 _v57.frame_id = str[start:end] 01506 _x = _v56 01507 start = end 01508 end += 8 01509 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01510 start = end 01511 end += 4 01512 (length,) = _struct_I.unpack(str[start:end]) 01513 start = end 01514 end += length 01515 _v56.encoding = str[start:end] 01516 _x = _v56 01517 start = end 01518 end += 5 01519 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 01520 start = end 01521 end += 4 01522 (length,) = _struct_I.unpack(str[start:end]) 01523 start = end 01524 end += length 01525 _v56.data = str[start:end] 01526 _v59 = _v52.disparity_image 01527 _v60 = _v59.header 01528 start = end 01529 end += 4 01530 (_v60.seq,) = _struct_I.unpack(str[start:end]) 01531 _v61 = _v60.stamp 01532 _x = _v61 01533 start = end 01534 end += 8 01535 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01536 start = end 01537 end += 4 01538 (length,) = _struct_I.unpack(str[start:end]) 01539 start = end 01540 end += length 01541 _v60.frame_id = str[start:end] 01542 _x = _v59 01543 start = end 01544 end += 8 01545 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01546 start = end 01547 end += 4 01548 (length,) = _struct_I.unpack(str[start:end]) 01549 start = end 01550 end += length 01551 _v59.encoding = str[start:end] 01552 _x = _v59 01553 start = end 01554 end += 5 01555 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 01556 start = end 01557 end += 4 01558 (length,) = _struct_I.unpack(str[start:end]) 01559 start = end 01560 end += length 01561 _v59.data = str[start:end] 01562 _v62 = _v52.cam_info 01563 _v63 = _v62.header 01564 start = end 01565 end += 4 01566 (_v63.seq,) = _struct_I.unpack(str[start:end]) 01567 _v64 = _v63.stamp 01568 _x = _v64 01569 start = end 01570 end += 8 01571 (_x.secs, _x.nsecs,) = _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 _v63.frame_id = str[start:end] 01578 _x = _v62 01579 start = end 01580 end += 8 01581 (_x.height, _x.width,) = _struct_2I.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 _v62.distortion_model = str[start:end] 01588 start = end 01589 end += 4 01590 (length,) = _struct_I.unpack(str[start:end]) 01591 pattern = '<%sd'%length 01592 start = end 01593 end += struct.calcsize(pattern) 01594 _v62.D = struct.unpack(pattern, str[start:end]) 01595 start = end 01596 end += 72 01597 _v62.K = _struct_9d.unpack(str[start:end]) 01598 start = end 01599 end += 72 01600 _v62.R = _struct_9d.unpack(str[start:end]) 01601 start = end 01602 end += 96 01603 _v62.P = _struct_12d.unpack(str[start:end]) 01604 _x = _v62 01605 start = end 01606 end += 8 01607 (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end]) 01608 _v65 = _v62.roi 01609 _x = _v65 01610 start = end 01611 end += 17 01612 (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end]) 01613 _v65.do_rectify = bool(_v65.do_rectify) 01614 _v66 = _v52.roi_box_pose 01615 _v67 = _v66.header 01616 start = end 01617 end += 4 01618 (_v67.seq,) = _struct_I.unpack(str[start:end]) 01619 _v68 = _v67.stamp 01620 _x = _v68 01621 start = end 01622 end += 8 01623 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01624 start = end 01625 end += 4 01626 (length,) = _struct_I.unpack(str[start:end]) 01627 start = end 01628 end += length 01629 _v67.frame_id = str[start:end] 01630 _v69 = _v66.pose 01631 _v70 = _v69.position 01632 _x = _v70 01633 start = end 01634 end += 24 01635 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01636 _v71 = _v69.orientation 01637 _x = _v71 01638 start = end 01639 end += 32 01640 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01641 _v72 = _v52.roi_box_dims 01642 _x = _v72 01643 start = end 01644 end += 24 01645 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01646 start = end 01647 end += 4 01648 (length,) = _struct_I.unpack(str[start:end]) 01649 start = end 01650 end += length 01651 val1.collision_name = str[start:end] 01652 self.grasp.moved_obstacles.append(val1) 01653 return self 01654 except struct.error as e: 01655 raise roslib.message.DeserializationError(e) #most likely buffer underfill 01656 01657 01658 def serialize_numpy(self, buff, numpy): 01659 """ 01660 serialize message with numpy array types into buffer 01661 @param buff: buffer 01662 @type buff: StringIO 01663 @param numpy: numpy python module 01664 @type numpy module 01665 """ 01666 try: 01667 _x = self.arm_name 01668 length = len(_x) 01669 buff.write(struct.pack('<I%ss'%length, length, _x)) 01670 _x = self 01671 buff.write(_struct_3I.pack(_x.gripper_pose.header.seq, _x.gripper_pose.header.stamp.secs, _x.gripper_pose.header.stamp.nsecs)) 01672 _x = self.gripper_pose.header.frame_id 01673 length = len(_x) 01674 buff.write(struct.pack('<I%ss'%length, length, _x)) 01675 _x = self 01676 buff.write(_struct_7df.pack(_x.gripper_pose.pose.position.x, _x.gripper_pose.pose.position.y, _x.gripper_pose.pose.position.z, _x.gripper_pose.pose.orientation.x, _x.gripper_pose.pose.orientation.y, _x.gripper_pose.pose.orientation.z, _x.gripper_pose.pose.orientation.w, _x.gripper_opening)) 01677 _x = self.object.reference_frame_id 01678 length = len(_x) 01679 buff.write(struct.pack('<I%ss'%length, length, _x)) 01680 length = len(self.object.potential_models) 01681 buff.write(_struct_I.pack(length)) 01682 for val1 in self.object.potential_models: 01683 buff.write(_struct_i.pack(val1.model_id)) 01684 _v73 = val1.pose 01685 _v74 = _v73.header 01686 buff.write(_struct_I.pack(_v74.seq)) 01687 _v75 = _v74.stamp 01688 _x = _v75 01689 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01690 _x = _v74.frame_id 01691 length = len(_x) 01692 buff.write(struct.pack('<I%ss'%length, length, _x)) 01693 _v76 = _v73.pose 01694 _v77 = _v76.position 01695 _x = _v77 01696 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01697 _v78 = _v76.orientation 01698 _x = _v78 01699 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01700 buff.write(_struct_f.pack(val1.confidence)) 01701 _x = val1.detector_name 01702 length = len(_x) 01703 buff.write(struct.pack('<I%ss'%length, length, _x)) 01704 _x = self 01705 buff.write(_struct_3I.pack(_x.object.cluster.header.seq, _x.object.cluster.header.stamp.secs, _x.object.cluster.header.stamp.nsecs)) 01706 _x = self.object.cluster.header.frame_id 01707 length = len(_x) 01708 buff.write(struct.pack('<I%ss'%length, length, _x)) 01709 length = len(self.object.cluster.points) 01710 buff.write(_struct_I.pack(length)) 01711 for val1 in self.object.cluster.points: 01712 _x = val1 01713 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 01714 length = len(self.object.cluster.channels) 01715 buff.write(_struct_I.pack(length)) 01716 for val1 in self.object.cluster.channels: 01717 _x = val1.name 01718 length = len(_x) 01719 buff.write(struct.pack('<I%ss'%length, length, _x)) 01720 length = len(val1.values) 01721 buff.write(_struct_I.pack(length)) 01722 pattern = '<%sf'%length 01723 buff.write(val1.values.tostring()) 01724 _x = self 01725 buff.write(_struct_3I.pack(_x.object.region.cloud.header.seq, _x.object.region.cloud.header.stamp.secs, _x.object.region.cloud.header.stamp.nsecs)) 01726 _x = self.object.region.cloud.header.frame_id 01727 length = len(_x) 01728 buff.write(struct.pack('<I%ss'%length, length, _x)) 01729 _x = self 01730 buff.write(_struct_2I.pack(_x.object.region.cloud.height, _x.object.region.cloud.width)) 01731 length = len(self.object.region.cloud.fields) 01732 buff.write(_struct_I.pack(length)) 01733 for val1 in self.object.region.cloud.fields: 01734 _x = val1.name 01735 length = len(_x) 01736 buff.write(struct.pack('<I%ss'%length, length, _x)) 01737 _x = val1 01738 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 01739 _x = self 01740 buff.write(_struct_B2I.pack(_x.object.region.cloud.is_bigendian, _x.object.region.cloud.point_step, _x.object.region.cloud.row_step)) 01741 _x = self.object.region.cloud.data 01742 length = len(_x) 01743 # - if encoded as a list instead, serialize as bytes instead of string 01744 if type(_x) in [list, tuple]: 01745 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01746 else: 01747 buff.write(struct.pack('<I%ss'%length, length, _x)) 01748 buff.write(_struct_B.pack(self.object.region.cloud.is_dense)) 01749 length = len(self.object.region.mask) 01750 buff.write(_struct_I.pack(length)) 01751 pattern = '<%si'%length 01752 buff.write(self.object.region.mask.tostring()) 01753 _x = self 01754 buff.write(_struct_3I.pack(_x.object.region.image.header.seq, _x.object.region.image.header.stamp.secs, _x.object.region.image.header.stamp.nsecs)) 01755 _x = self.object.region.image.header.frame_id 01756 length = len(_x) 01757 buff.write(struct.pack('<I%ss'%length, length, _x)) 01758 _x = self 01759 buff.write(_struct_2I.pack(_x.object.region.image.height, _x.object.region.image.width)) 01760 _x = self.object.region.image.encoding 01761 length = len(_x) 01762 buff.write(struct.pack('<I%ss'%length, length, _x)) 01763 _x = self 01764 buff.write(_struct_BI.pack(_x.object.region.image.is_bigendian, _x.object.region.image.step)) 01765 _x = self.object.region.image.data 01766 length = len(_x) 01767 # - if encoded as a list instead, serialize as bytes instead of string 01768 if type(_x) in [list, tuple]: 01769 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01770 else: 01771 buff.write(struct.pack('<I%ss'%length, length, _x)) 01772 _x = self 01773 buff.write(_struct_3I.pack(_x.object.region.disparity_image.header.seq, _x.object.region.disparity_image.header.stamp.secs, _x.object.region.disparity_image.header.stamp.nsecs)) 01774 _x = self.object.region.disparity_image.header.frame_id 01775 length = len(_x) 01776 buff.write(struct.pack('<I%ss'%length, length, _x)) 01777 _x = self 01778 buff.write(_struct_2I.pack(_x.object.region.disparity_image.height, _x.object.region.disparity_image.width)) 01779 _x = self.object.region.disparity_image.encoding 01780 length = len(_x) 01781 buff.write(struct.pack('<I%ss'%length, length, _x)) 01782 _x = self 01783 buff.write(_struct_BI.pack(_x.object.region.disparity_image.is_bigendian, _x.object.region.disparity_image.step)) 01784 _x = self.object.region.disparity_image.data 01785 length = len(_x) 01786 # - if encoded as a list instead, serialize as bytes instead of string 01787 if type(_x) in [list, tuple]: 01788 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01789 else: 01790 buff.write(struct.pack('<I%ss'%length, length, _x)) 01791 _x = self 01792 buff.write(_struct_3I.pack(_x.object.region.cam_info.header.seq, _x.object.region.cam_info.header.stamp.secs, _x.object.region.cam_info.header.stamp.nsecs)) 01793 _x = self.object.region.cam_info.header.frame_id 01794 length = len(_x) 01795 buff.write(struct.pack('<I%ss'%length, length, _x)) 01796 _x = self 01797 buff.write(_struct_2I.pack(_x.object.region.cam_info.height, _x.object.region.cam_info.width)) 01798 _x = self.object.region.cam_info.distortion_model 01799 length = len(_x) 01800 buff.write(struct.pack('<I%ss'%length, length, _x)) 01801 length = len(self.object.region.cam_info.D) 01802 buff.write(_struct_I.pack(length)) 01803 pattern = '<%sd'%length 01804 buff.write(self.object.region.cam_info.D.tostring()) 01805 buff.write(self.object.region.cam_info.K.tostring()) 01806 buff.write(self.object.region.cam_info.R.tostring()) 01807 buff.write(self.object.region.cam_info.P.tostring()) 01808 _x = self 01809 buff.write(_struct_6IB3I.pack(_x.object.region.cam_info.binning_x, _x.object.region.cam_info.binning_y, _x.object.region.cam_info.roi.x_offset, _x.object.region.cam_info.roi.y_offset, _x.object.region.cam_info.roi.height, _x.object.region.cam_info.roi.width, _x.object.region.cam_info.roi.do_rectify, _x.object.region.roi_box_pose.header.seq, _x.object.region.roi_box_pose.header.stamp.secs, _x.object.region.roi_box_pose.header.stamp.nsecs)) 01810 _x = self.object.region.roi_box_pose.header.frame_id 01811 length = len(_x) 01812 buff.write(struct.pack('<I%ss'%length, length, _x)) 01813 _x = self 01814 buff.write(_struct_10d.pack(_x.object.region.roi_box_pose.pose.position.x, _x.object.region.roi_box_pose.pose.position.y, _x.object.region.roi_box_pose.pose.position.z, _x.object.region.roi_box_pose.pose.orientation.x, _x.object.region.roi_box_pose.pose.orientation.y, _x.object.region.roi_box_pose.pose.orientation.z, _x.object.region.roi_box_pose.pose.orientation.w, _x.object.region.roi_box_dims.x, _x.object.region.roi_box_dims.y, _x.object.region.roi_box_dims.z)) 01815 _x = self.object.collision_name 01816 length = len(_x) 01817 buff.write(struct.pack('<I%ss'%length, length, _x)) 01818 _x = self 01819 buff.write(_struct_3I.pack(_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs)) 01820 _x = self.grasp.pre_grasp_posture.header.frame_id 01821 length = len(_x) 01822 buff.write(struct.pack('<I%ss'%length, length, _x)) 01823 length = len(self.grasp.pre_grasp_posture.name) 01824 buff.write(_struct_I.pack(length)) 01825 for val1 in self.grasp.pre_grasp_posture.name: 01826 length = len(val1) 01827 buff.write(struct.pack('<I%ss'%length, length, val1)) 01828 length = len(self.grasp.pre_grasp_posture.position) 01829 buff.write(_struct_I.pack(length)) 01830 pattern = '<%sd'%length 01831 buff.write(self.grasp.pre_grasp_posture.position.tostring()) 01832 length = len(self.grasp.pre_grasp_posture.velocity) 01833 buff.write(_struct_I.pack(length)) 01834 pattern = '<%sd'%length 01835 buff.write(self.grasp.pre_grasp_posture.velocity.tostring()) 01836 length = len(self.grasp.pre_grasp_posture.effort) 01837 buff.write(_struct_I.pack(length)) 01838 pattern = '<%sd'%length 01839 buff.write(self.grasp.pre_grasp_posture.effort.tostring()) 01840 _x = self 01841 buff.write(_struct_3I.pack(_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs)) 01842 _x = self.grasp.grasp_posture.header.frame_id 01843 length = len(_x) 01844 buff.write(struct.pack('<I%ss'%length, length, _x)) 01845 length = len(self.grasp.grasp_posture.name) 01846 buff.write(_struct_I.pack(length)) 01847 for val1 in self.grasp.grasp_posture.name: 01848 length = len(val1) 01849 buff.write(struct.pack('<I%ss'%length, length, val1)) 01850 length = len(self.grasp.grasp_posture.position) 01851 buff.write(_struct_I.pack(length)) 01852 pattern = '<%sd'%length 01853 buff.write(self.grasp.grasp_posture.position.tostring()) 01854 length = len(self.grasp.grasp_posture.velocity) 01855 buff.write(_struct_I.pack(length)) 01856 pattern = '<%sd'%length 01857 buff.write(self.grasp.grasp_posture.velocity.tostring()) 01858 length = len(self.grasp.grasp_posture.effort) 01859 buff.write(_struct_I.pack(length)) 01860 pattern = '<%sd'%length 01861 buff.write(self.grasp.grasp_posture.effort.tostring()) 01862 _x = self 01863 buff.write(_struct_8dB2f.pack(_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance)) 01864 length = len(self.grasp.moved_obstacles) 01865 buff.write(_struct_I.pack(length)) 01866 for val1 in self.grasp.moved_obstacles: 01867 _x = val1.reference_frame_id 01868 length = len(_x) 01869 buff.write(struct.pack('<I%ss'%length, length, _x)) 01870 length = len(val1.potential_models) 01871 buff.write(_struct_I.pack(length)) 01872 for val2 in val1.potential_models: 01873 buff.write(_struct_i.pack(val2.model_id)) 01874 _v79 = val2.pose 01875 _v80 = _v79.header 01876 buff.write(_struct_I.pack(_v80.seq)) 01877 _v81 = _v80.stamp 01878 _x = _v81 01879 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01880 _x = _v80.frame_id 01881 length = len(_x) 01882 buff.write(struct.pack('<I%ss'%length, length, _x)) 01883 _v82 = _v79.pose 01884 _v83 = _v82.position 01885 _x = _v83 01886 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01887 _v84 = _v82.orientation 01888 _x = _v84 01889 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01890 buff.write(_struct_f.pack(val2.confidence)) 01891 _x = val2.detector_name 01892 length = len(_x) 01893 buff.write(struct.pack('<I%ss'%length, length, _x)) 01894 _v85 = val1.cluster 01895 _v86 = _v85.header 01896 buff.write(_struct_I.pack(_v86.seq)) 01897 _v87 = _v86.stamp 01898 _x = _v87 01899 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01900 _x = _v86.frame_id 01901 length = len(_x) 01902 buff.write(struct.pack('<I%ss'%length, length, _x)) 01903 length = len(_v85.points) 01904 buff.write(_struct_I.pack(length)) 01905 for val3 in _v85.points: 01906 _x = val3 01907 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 01908 length = len(_v85.channels) 01909 buff.write(_struct_I.pack(length)) 01910 for val3 in _v85.channels: 01911 _x = val3.name 01912 length = len(_x) 01913 buff.write(struct.pack('<I%ss'%length, length, _x)) 01914 length = len(val3.values) 01915 buff.write(_struct_I.pack(length)) 01916 pattern = '<%sf'%length 01917 buff.write(val3.values.tostring()) 01918 _v88 = val1.region 01919 _v89 = _v88.cloud 01920 _v90 = _v89.header 01921 buff.write(_struct_I.pack(_v90.seq)) 01922 _v91 = _v90.stamp 01923 _x = _v91 01924 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01925 _x = _v90.frame_id 01926 length = len(_x) 01927 buff.write(struct.pack('<I%ss'%length, length, _x)) 01928 _x = _v89 01929 buff.write(_struct_2I.pack(_x.height, _x.width)) 01930 length = len(_v89.fields) 01931 buff.write(_struct_I.pack(length)) 01932 for val4 in _v89.fields: 01933 _x = val4.name 01934 length = len(_x) 01935 buff.write(struct.pack('<I%ss'%length, length, _x)) 01936 _x = val4 01937 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 01938 _x = _v89 01939 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step)) 01940 _x = _v89.data 01941 length = len(_x) 01942 # - if encoded as a list instead, serialize as bytes instead of string 01943 if type(_x) in [list, tuple]: 01944 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01945 else: 01946 buff.write(struct.pack('<I%ss'%length, length, _x)) 01947 buff.write(_struct_B.pack(_v89.is_dense)) 01948 length = len(_v88.mask) 01949 buff.write(_struct_I.pack(length)) 01950 pattern = '<%si'%length 01951 buff.write(_v88.mask.tostring()) 01952 _v92 = _v88.image 01953 _v93 = _v92.header 01954 buff.write(_struct_I.pack(_v93.seq)) 01955 _v94 = _v93.stamp 01956 _x = _v94 01957 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01958 _x = _v93.frame_id 01959 length = len(_x) 01960 buff.write(struct.pack('<I%ss'%length, length, _x)) 01961 _x = _v92 01962 buff.write(_struct_2I.pack(_x.height, _x.width)) 01963 _x = _v92.encoding 01964 length = len(_x) 01965 buff.write(struct.pack('<I%ss'%length, length, _x)) 01966 _x = _v92 01967 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 01968 _x = _v92.data 01969 length = len(_x) 01970 # - if encoded as a list instead, serialize as bytes instead of string 01971 if type(_x) in [list, tuple]: 01972 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01973 else: 01974 buff.write(struct.pack('<I%ss'%length, length, _x)) 01975 _v95 = _v88.disparity_image 01976 _v96 = _v95.header 01977 buff.write(_struct_I.pack(_v96.seq)) 01978 _v97 = _v96.stamp 01979 _x = _v97 01980 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01981 _x = _v96.frame_id 01982 length = len(_x) 01983 buff.write(struct.pack('<I%ss'%length, length, _x)) 01984 _x = _v95 01985 buff.write(_struct_2I.pack(_x.height, _x.width)) 01986 _x = _v95.encoding 01987 length = len(_x) 01988 buff.write(struct.pack('<I%ss'%length, length, _x)) 01989 _x = _v95 01990 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 01991 _x = _v95.data 01992 length = len(_x) 01993 # - if encoded as a list instead, serialize as bytes instead of string 01994 if type(_x) in [list, tuple]: 01995 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01996 else: 01997 buff.write(struct.pack('<I%ss'%length, length, _x)) 01998 _v98 = _v88.cam_info 01999 _v99 = _v98.header 02000 buff.write(_struct_I.pack(_v99.seq)) 02001 _v100 = _v99.stamp 02002 _x = _v100 02003 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 02004 _x = _v99.frame_id 02005 length = len(_x) 02006 buff.write(struct.pack('<I%ss'%length, length, _x)) 02007 _x = _v98 02008 buff.write(_struct_2I.pack(_x.height, _x.width)) 02009 _x = _v98.distortion_model 02010 length = len(_x) 02011 buff.write(struct.pack('<I%ss'%length, length, _x)) 02012 length = len(_v98.D) 02013 buff.write(_struct_I.pack(length)) 02014 pattern = '<%sd'%length 02015 buff.write(_v98.D.tostring()) 02016 buff.write(_v98.K.tostring()) 02017 buff.write(_v98.R.tostring()) 02018 buff.write(_v98.P.tostring()) 02019 _x = _v98 02020 buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y)) 02021 _v101 = _v98.roi 02022 _x = _v101 02023 buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify)) 02024 _v102 = _v88.roi_box_pose 02025 _v103 = _v102.header 02026 buff.write(_struct_I.pack(_v103.seq)) 02027 _v104 = _v103.stamp 02028 _x = _v104 02029 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 02030 _x = _v103.frame_id 02031 length = len(_x) 02032 buff.write(struct.pack('<I%ss'%length, length, _x)) 02033 _v105 = _v102.pose 02034 _v106 = _v105.position 02035 _x = _v106 02036 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 02037 _v107 = _v105.orientation 02038 _x = _v107 02039 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 02040 _v108 = _v88.roi_box_dims 02041 _x = _v108 02042 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 02043 _x = val1.collision_name 02044 length = len(_x) 02045 buff.write(struct.pack('<I%ss'%length, length, _x)) 02046 except struct.error as se: self._check_types(se) 02047 except TypeError as te: self._check_types(te) 02048 02049 def deserialize_numpy(self, str, numpy): 02050 """ 02051 unpack serialized message in str into this message instance using numpy for array types 02052 @param str: byte array of serialized message 02053 @type str: str 02054 @param numpy: numpy python module 02055 @type numpy: module 02056 """ 02057 try: 02058 if self.gripper_pose is None: 02059 self.gripper_pose = geometry_msgs.msg.PoseStamped() 02060 if self.object is None: 02061 self.object = object_manipulation_msgs.msg.GraspableObject() 02062 if self.grasp is None: 02063 self.grasp = object_manipulation_msgs.msg.Grasp() 02064 end = 0 02065 start = end 02066 end += 4 02067 (length,) = _struct_I.unpack(str[start:end]) 02068 start = end 02069 end += length 02070 self.arm_name = str[start:end] 02071 _x = self 02072 start = end 02073 end += 12 02074 (_x.gripper_pose.header.seq, _x.gripper_pose.header.stamp.secs, _x.gripper_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02075 start = end 02076 end += 4 02077 (length,) = _struct_I.unpack(str[start:end]) 02078 start = end 02079 end += length 02080 self.gripper_pose.header.frame_id = str[start:end] 02081 _x = self 02082 start = end 02083 end += 60 02084 (_x.gripper_pose.pose.position.x, _x.gripper_pose.pose.position.y, _x.gripper_pose.pose.position.z, _x.gripper_pose.pose.orientation.x, _x.gripper_pose.pose.orientation.y, _x.gripper_pose.pose.orientation.z, _x.gripper_pose.pose.orientation.w, _x.gripper_opening,) = _struct_7df.unpack(str[start:end]) 02085 start = end 02086 end += 4 02087 (length,) = _struct_I.unpack(str[start:end]) 02088 start = end 02089 end += length 02090 self.object.reference_frame_id = str[start:end] 02091 start = end 02092 end += 4 02093 (length,) = _struct_I.unpack(str[start:end]) 02094 self.object.potential_models = [] 02095 for i in range(0, length): 02096 val1 = household_objects_database_msgs.msg.DatabaseModelPose() 02097 start = end 02098 end += 4 02099 (val1.model_id,) = _struct_i.unpack(str[start:end]) 02100 _v109 = val1.pose 02101 _v110 = _v109.header 02102 start = end 02103 end += 4 02104 (_v110.seq,) = _struct_I.unpack(str[start:end]) 02105 _v111 = _v110.stamp 02106 _x = _v111 02107 start = end 02108 end += 8 02109 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02110 start = end 02111 end += 4 02112 (length,) = _struct_I.unpack(str[start:end]) 02113 start = end 02114 end += length 02115 _v110.frame_id = str[start:end] 02116 _v112 = _v109.pose 02117 _v113 = _v112.position 02118 _x = _v113 02119 start = end 02120 end += 24 02121 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 02122 _v114 = _v112.orientation 02123 _x = _v114 02124 start = end 02125 end += 32 02126 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 02127 start = end 02128 end += 4 02129 (val1.confidence,) = _struct_f.unpack(str[start:end]) 02130 start = end 02131 end += 4 02132 (length,) = _struct_I.unpack(str[start:end]) 02133 start = end 02134 end += length 02135 val1.detector_name = str[start:end] 02136 self.object.potential_models.append(val1) 02137 _x = self 02138 start = end 02139 end += 12 02140 (_x.object.cluster.header.seq, _x.object.cluster.header.stamp.secs, _x.object.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02141 start = end 02142 end += 4 02143 (length,) = _struct_I.unpack(str[start:end]) 02144 start = end 02145 end += length 02146 self.object.cluster.header.frame_id = str[start:end] 02147 start = end 02148 end += 4 02149 (length,) = _struct_I.unpack(str[start:end]) 02150 self.object.cluster.points = [] 02151 for i in range(0, length): 02152 val1 = geometry_msgs.msg.Point32() 02153 _x = val1 02154 start = end 02155 end += 12 02156 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 02157 self.object.cluster.points.append(val1) 02158 start = end 02159 end += 4 02160 (length,) = _struct_I.unpack(str[start:end]) 02161 self.object.cluster.channels = [] 02162 for i in range(0, length): 02163 val1 = sensor_msgs.msg.ChannelFloat32() 02164 start = end 02165 end += 4 02166 (length,) = _struct_I.unpack(str[start:end]) 02167 start = end 02168 end += length 02169 val1.name = str[start:end] 02170 start = end 02171 end += 4 02172 (length,) = _struct_I.unpack(str[start:end]) 02173 pattern = '<%sf'%length 02174 start = end 02175 end += struct.calcsize(pattern) 02176 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 02177 self.object.cluster.channels.append(val1) 02178 _x = self 02179 start = end 02180 end += 12 02181 (_x.object.region.cloud.header.seq, _x.object.region.cloud.header.stamp.secs, _x.object.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02182 start = end 02183 end += 4 02184 (length,) = _struct_I.unpack(str[start:end]) 02185 start = end 02186 end += length 02187 self.object.region.cloud.header.frame_id = str[start:end] 02188 _x = self 02189 start = end 02190 end += 8 02191 (_x.object.region.cloud.height, _x.object.region.cloud.width,) = _struct_2I.unpack(str[start:end]) 02192 start = end 02193 end += 4 02194 (length,) = _struct_I.unpack(str[start:end]) 02195 self.object.region.cloud.fields = [] 02196 for i in range(0, length): 02197 val1 = sensor_msgs.msg.PointField() 02198 start = end 02199 end += 4 02200 (length,) = _struct_I.unpack(str[start:end]) 02201 start = end 02202 end += length 02203 val1.name = str[start:end] 02204 _x = val1 02205 start = end 02206 end += 9 02207 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 02208 self.object.region.cloud.fields.append(val1) 02209 _x = self 02210 start = end 02211 end += 9 02212 (_x.object.region.cloud.is_bigendian, _x.object.region.cloud.point_step, _x.object.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end]) 02213 self.object.region.cloud.is_bigendian = bool(self.object.region.cloud.is_bigendian) 02214 start = end 02215 end += 4 02216 (length,) = _struct_I.unpack(str[start:end]) 02217 start = end 02218 end += length 02219 self.object.region.cloud.data = str[start:end] 02220 start = end 02221 end += 1 02222 (self.object.region.cloud.is_dense,) = _struct_B.unpack(str[start:end]) 02223 self.object.region.cloud.is_dense = bool(self.object.region.cloud.is_dense) 02224 start = end 02225 end += 4 02226 (length,) = _struct_I.unpack(str[start:end]) 02227 pattern = '<%si'%length 02228 start = end 02229 end += struct.calcsize(pattern) 02230 self.object.region.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 02231 _x = self 02232 start = end 02233 end += 12 02234 (_x.object.region.image.header.seq, _x.object.region.image.header.stamp.secs, _x.object.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02235 start = end 02236 end += 4 02237 (length,) = _struct_I.unpack(str[start:end]) 02238 start = end 02239 end += length 02240 self.object.region.image.header.frame_id = str[start:end] 02241 _x = self 02242 start = end 02243 end += 8 02244 (_x.object.region.image.height, _x.object.region.image.width,) = _struct_2I.unpack(str[start:end]) 02245 start = end 02246 end += 4 02247 (length,) = _struct_I.unpack(str[start:end]) 02248 start = end 02249 end += length 02250 self.object.region.image.encoding = str[start:end] 02251 _x = self 02252 start = end 02253 end += 5 02254 (_x.object.region.image.is_bigendian, _x.object.region.image.step,) = _struct_BI.unpack(str[start:end]) 02255 start = end 02256 end += 4 02257 (length,) = _struct_I.unpack(str[start:end]) 02258 start = end 02259 end += length 02260 self.object.region.image.data = str[start:end] 02261 _x = self 02262 start = end 02263 end += 12 02264 (_x.object.region.disparity_image.header.seq, _x.object.region.disparity_image.header.stamp.secs, _x.object.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02265 start = end 02266 end += 4 02267 (length,) = _struct_I.unpack(str[start:end]) 02268 start = end 02269 end += length 02270 self.object.region.disparity_image.header.frame_id = str[start:end] 02271 _x = self 02272 start = end 02273 end += 8 02274 (_x.object.region.disparity_image.height, _x.object.region.disparity_image.width,) = _struct_2I.unpack(str[start:end]) 02275 start = end 02276 end += 4 02277 (length,) = _struct_I.unpack(str[start:end]) 02278 start = end 02279 end += length 02280 self.object.region.disparity_image.encoding = str[start:end] 02281 _x = self 02282 start = end 02283 end += 5 02284 (_x.object.region.disparity_image.is_bigendian, _x.object.region.disparity_image.step,) = _struct_BI.unpack(str[start:end]) 02285 start = end 02286 end += 4 02287 (length,) = _struct_I.unpack(str[start:end]) 02288 start = end 02289 end += length 02290 self.object.region.disparity_image.data = str[start:end] 02291 _x = self 02292 start = end 02293 end += 12 02294 (_x.object.region.cam_info.header.seq, _x.object.region.cam_info.header.stamp.secs, _x.object.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02295 start = end 02296 end += 4 02297 (length,) = _struct_I.unpack(str[start:end]) 02298 start = end 02299 end += length 02300 self.object.region.cam_info.header.frame_id = str[start:end] 02301 _x = self 02302 start = end 02303 end += 8 02304 (_x.object.region.cam_info.height, _x.object.region.cam_info.width,) = _struct_2I.unpack(str[start:end]) 02305 start = end 02306 end += 4 02307 (length,) = _struct_I.unpack(str[start:end]) 02308 start = end 02309 end += length 02310 self.object.region.cam_info.distortion_model = str[start:end] 02311 start = end 02312 end += 4 02313 (length,) = _struct_I.unpack(str[start:end]) 02314 pattern = '<%sd'%length 02315 start = end 02316 end += struct.calcsize(pattern) 02317 self.object.region.cam_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02318 start = end 02319 end += 72 02320 self.object.region.cam_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 02321 start = end 02322 end += 72 02323 self.object.region.cam_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 02324 start = end 02325 end += 96 02326 self.object.region.cam_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12) 02327 _x = self 02328 start = end 02329 end += 37 02330 (_x.object.region.cam_info.binning_x, _x.object.region.cam_info.binning_y, _x.object.region.cam_info.roi.x_offset, _x.object.region.cam_info.roi.y_offset, _x.object.region.cam_info.roi.height, _x.object.region.cam_info.roi.width, _x.object.region.cam_info.roi.do_rectify, _x.object.region.roi_box_pose.header.seq, _x.object.region.roi_box_pose.header.stamp.secs, _x.object.region.roi_box_pose.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end]) 02331 self.object.region.cam_info.roi.do_rectify = bool(self.object.region.cam_info.roi.do_rectify) 02332 start = end 02333 end += 4 02334 (length,) = _struct_I.unpack(str[start:end]) 02335 start = end 02336 end += length 02337 self.object.region.roi_box_pose.header.frame_id = str[start:end] 02338 _x = self 02339 start = end 02340 end += 80 02341 (_x.object.region.roi_box_pose.pose.position.x, _x.object.region.roi_box_pose.pose.position.y, _x.object.region.roi_box_pose.pose.position.z, _x.object.region.roi_box_pose.pose.orientation.x, _x.object.region.roi_box_pose.pose.orientation.y, _x.object.region.roi_box_pose.pose.orientation.z, _x.object.region.roi_box_pose.pose.orientation.w, _x.object.region.roi_box_dims.x, _x.object.region.roi_box_dims.y, _x.object.region.roi_box_dims.z,) = _struct_10d.unpack(str[start:end]) 02342 start = end 02343 end += 4 02344 (length,) = _struct_I.unpack(str[start:end]) 02345 start = end 02346 end += length 02347 self.object.collision_name = str[start:end] 02348 _x = self 02349 start = end 02350 end += 12 02351 (_x.grasp.pre_grasp_posture.header.seq, _x.grasp.pre_grasp_posture.header.stamp.secs, _x.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02352 start = end 02353 end += 4 02354 (length,) = _struct_I.unpack(str[start:end]) 02355 start = end 02356 end += length 02357 self.grasp.pre_grasp_posture.header.frame_id = str[start:end] 02358 start = end 02359 end += 4 02360 (length,) = _struct_I.unpack(str[start:end]) 02361 self.grasp.pre_grasp_posture.name = [] 02362 for i in range(0, length): 02363 start = end 02364 end += 4 02365 (length,) = _struct_I.unpack(str[start:end]) 02366 start = end 02367 end += length 02368 val1 = str[start:end] 02369 self.grasp.pre_grasp_posture.name.append(val1) 02370 start = end 02371 end += 4 02372 (length,) = _struct_I.unpack(str[start:end]) 02373 pattern = '<%sd'%length 02374 start = end 02375 end += struct.calcsize(pattern) 02376 self.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02377 start = end 02378 end += 4 02379 (length,) = _struct_I.unpack(str[start:end]) 02380 pattern = '<%sd'%length 02381 start = end 02382 end += struct.calcsize(pattern) 02383 self.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02384 start = end 02385 end += 4 02386 (length,) = _struct_I.unpack(str[start:end]) 02387 pattern = '<%sd'%length 02388 start = end 02389 end += struct.calcsize(pattern) 02390 self.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02391 _x = self 02392 start = end 02393 end += 12 02394 (_x.grasp.grasp_posture.header.seq, _x.grasp.grasp_posture.header.stamp.secs, _x.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 02395 start = end 02396 end += 4 02397 (length,) = _struct_I.unpack(str[start:end]) 02398 start = end 02399 end += length 02400 self.grasp.grasp_posture.header.frame_id = str[start:end] 02401 start = end 02402 end += 4 02403 (length,) = _struct_I.unpack(str[start:end]) 02404 self.grasp.grasp_posture.name = [] 02405 for i in range(0, length): 02406 start = end 02407 end += 4 02408 (length,) = _struct_I.unpack(str[start:end]) 02409 start = end 02410 end += length 02411 val1 = str[start:end] 02412 self.grasp.grasp_posture.name.append(val1) 02413 start = end 02414 end += 4 02415 (length,) = _struct_I.unpack(str[start:end]) 02416 pattern = '<%sd'%length 02417 start = end 02418 end += struct.calcsize(pattern) 02419 self.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02420 start = end 02421 end += 4 02422 (length,) = _struct_I.unpack(str[start:end]) 02423 pattern = '<%sd'%length 02424 start = end 02425 end += struct.calcsize(pattern) 02426 self.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02427 start = end 02428 end += 4 02429 (length,) = _struct_I.unpack(str[start:end]) 02430 pattern = '<%sd'%length 02431 start = end 02432 end += struct.calcsize(pattern) 02433 self.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02434 _x = self 02435 start = end 02436 end += 73 02437 (_x.grasp.grasp_pose.position.x, _x.grasp.grasp_pose.position.y, _x.grasp.grasp_pose.position.z, _x.grasp.grasp_pose.orientation.x, _x.grasp.grasp_pose.orientation.y, _x.grasp.grasp_pose.orientation.z, _x.grasp.grasp_pose.orientation.w, _x.grasp.success_probability, _x.grasp.cluster_rep, _x.grasp.desired_approach_distance, _x.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end]) 02438 self.grasp.cluster_rep = bool(self.grasp.cluster_rep) 02439 start = end 02440 end += 4 02441 (length,) = _struct_I.unpack(str[start:end]) 02442 self.grasp.moved_obstacles = [] 02443 for i in range(0, length): 02444 val1 = object_manipulation_msgs.msg.GraspableObject() 02445 start = end 02446 end += 4 02447 (length,) = _struct_I.unpack(str[start:end]) 02448 start = end 02449 end += length 02450 val1.reference_frame_id = str[start:end] 02451 start = end 02452 end += 4 02453 (length,) = _struct_I.unpack(str[start:end]) 02454 val1.potential_models = [] 02455 for i in range(0, length): 02456 val2 = household_objects_database_msgs.msg.DatabaseModelPose() 02457 start = end 02458 end += 4 02459 (val2.model_id,) = _struct_i.unpack(str[start:end]) 02460 _v115 = val2.pose 02461 _v116 = _v115.header 02462 start = end 02463 end += 4 02464 (_v116.seq,) = _struct_I.unpack(str[start:end]) 02465 _v117 = _v116.stamp 02466 _x = _v117 02467 start = end 02468 end += 8 02469 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02470 start = end 02471 end += 4 02472 (length,) = _struct_I.unpack(str[start:end]) 02473 start = end 02474 end += length 02475 _v116.frame_id = str[start:end] 02476 _v118 = _v115.pose 02477 _v119 = _v118.position 02478 _x = _v119 02479 start = end 02480 end += 24 02481 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 02482 _v120 = _v118.orientation 02483 _x = _v120 02484 start = end 02485 end += 32 02486 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 02487 start = end 02488 end += 4 02489 (val2.confidence,) = _struct_f.unpack(str[start:end]) 02490 start = end 02491 end += 4 02492 (length,) = _struct_I.unpack(str[start:end]) 02493 start = end 02494 end += length 02495 val2.detector_name = str[start:end] 02496 val1.potential_models.append(val2) 02497 _v121 = val1.cluster 02498 _v122 = _v121.header 02499 start = end 02500 end += 4 02501 (_v122.seq,) = _struct_I.unpack(str[start:end]) 02502 _v123 = _v122.stamp 02503 _x = _v123 02504 start = end 02505 end += 8 02506 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02507 start = end 02508 end += 4 02509 (length,) = _struct_I.unpack(str[start:end]) 02510 start = end 02511 end += length 02512 _v122.frame_id = str[start:end] 02513 start = end 02514 end += 4 02515 (length,) = _struct_I.unpack(str[start:end]) 02516 _v121.points = [] 02517 for i in range(0, length): 02518 val3 = geometry_msgs.msg.Point32() 02519 _x = val3 02520 start = end 02521 end += 12 02522 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 02523 _v121.points.append(val3) 02524 start = end 02525 end += 4 02526 (length,) = _struct_I.unpack(str[start:end]) 02527 _v121.channels = [] 02528 for i in range(0, length): 02529 val3 = sensor_msgs.msg.ChannelFloat32() 02530 start = end 02531 end += 4 02532 (length,) = _struct_I.unpack(str[start:end]) 02533 start = end 02534 end += length 02535 val3.name = str[start:end] 02536 start = end 02537 end += 4 02538 (length,) = _struct_I.unpack(str[start:end]) 02539 pattern = '<%sf'%length 02540 start = end 02541 end += struct.calcsize(pattern) 02542 val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 02543 _v121.channels.append(val3) 02544 _v124 = val1.region 02545 _v125 = _v124.cloud 02546 _v126 = _v125.header 02547 start = end 02548 end += 4 02549 (_v126.seq,) = _struct_I.unpack(str[start:end]) 02550 _v127 = _v126.stamp 02551 _x = _v127 02552 start = end 02553 end += 8 02554 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02555 start = end 02556 end += 4 02557 (length,) = _struct_I.unpack(str[start:end]) 02558 start = end 02559 end += length 02560 _v126.frame_id = str[start:end] 02561 _x = _v125 02562 start = end 02563 end += 8 02564 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02565 start = end 02566 end += 4 02567 (length,) = _struct_I.unpack(str[start:end]) 02568 _v125.fields = [] 02569 for i in range(0, length): 02570 val4 = sensor_msgs.msg.PointField() 02571 start = end 02572 end += 4 02573 (length,) = _struct_I.unpack(str[start:end]) 02574 start = end 02575 end += length 02576 val4.name = str[start:end] 02577 _x = val4 02578 start = end 02579 end += 9 02580 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 02581 _v125.fields.append(val4) 02582 _x = _v125 02583 start = end 02584 end += 9 02585 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end]) 02586 _v125.is_bigendian = bool(_v125.is_bigendian) 02587 start = end 02588 end += 4 02589 (length,) = _struct_I.unpack(str[start:end]) 02590 start = end 02591 end += length 02592 _v125.data = str[start:end] 02593 start = end 02594 end += 1 02595 (_v125.is_dense,) = _struct_B.unpack(str[start:end]) 02596 _v125.is_dense = bool(_v125.is_dense) 02597 start = end 02598 end += 4 02599 (length,) = _struct_I.unpack(str[start:end]) 02600 pattern = '<%si'%length 02601 start = end 02602 end += struct.calcsize(pattern) 02603 _v124.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 02604 _v128 = _v124.image 02605 _v129 = _v128.header 02606 start = end 02607 end += 4 02608 (_v129.seq,) = _struct_I.unpack(str[start:end]) 02609 _v130 = _v129.stamp 02610 _x = _v130 02611 start = end 02612 end += 8 02613 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02614 start = end 02615 end += 4 02616 (length,) = _struct_I.unpack(str[start:end]) 02617 start = end 02618 end += length 02619 _v129.frame_id = str[start:end] 02620 _x = _v128 02621 start = end 02622 end += 8 02623 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02624 start = end 02625 end += 4 02626 (length,) = _struct_I.unpack(str[start:end]) 02627 start = end 02628 end += length 02629 _v128.encoding = str[start:end] 02630 _x = _v128 02631 start = end 02632 end += 5 02633 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 02634 start = end 02635 end += 4 02636 (length,) = _struct_I.unpack(str[start:end]) 02637 start = end 02638 end += length 02639 _v128.data = str[start:end] 02640 _v131 = _v124.disparity_image 02641 _v132 = _v131.header 02642 start = end 02643 end += 4 02644 (_v132.seq,) = _struct_I.unpack(str[start:end]) 02645 _v133 = _v132.stamp 02646 _x = _v133 02647 start = end 02648 end += 8 02649 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02650 start = end 02651 end += 4 02652 (length,) = _struct_I.unpack(str[start:end]) 02653 start = end 02654 end += length 02655 _v132.frame_id = str[start:end] 02656 _x = _v131 02657 start = end 02658 end += 8 02659 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02660 start = end 02661 end += 4 02662 (length,) = _struct_I.unpack(str[start:end]) 02663 start = end 02664 end += length 02665 _v131.encoding = str[start:end] 02666 _x = _v131 02667 start = end 02668 end += 5 02669 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 02670 start = end 02671 end += 4 02672 (length,) = _struct_I.unpack(str[start:end]) 02673 start = end 02674 end += length 02675 _v131.data = str[start:end] 02676 _v134 = _v124.cam_info 02677 _v135 = _v134.header 02678 start = end 02679 end += 4 02680 (_v135.seq,) = _struct_I.unpack(str[start:end]) 02681 _v136 = _v135.stamp 02682 _x = _v136 02683 start = end 02684 end += 8 02685 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02686 start = end 02687 end += 4 02688 (length,) = _struct_I.unpack(str[start:end]) 02689 start = end 02690 end += length 02691 _v135.frame_id = str[start:end] 02692 _x = _v134 02693 start = end 02694 end += 8 02695 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02696 start = end 02697 end += 4 02698 (length,) = _struct_I.unpack(str[start:end]) 02699 start = end 02700 end += length 02701 _v134.distortion_model = str[start:end] 02702 start = end 02703 end += 4 02704 (length,) = _struct_I.unpack(str[start:end]) 02705 pattern = '<%sd'%length 02706 start = end 02707 end += struct.calcsize(pattern) 02708 _v134.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02709 start = end 02710 end += 72 02711 _v134.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 02712 start = end 02713 end += 72 02714 _v134.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 02715 start = end 02716 end += 96 02717 _v134.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12) 02718 _x = _v134 02719 start = end 02720 end += 8 02721 (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end]) 02722 _v137 = _v134.roi 02723 _x = _v137 02724 start = end 02725 end += 17 02726 (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end]) 02727 _v137.do_rectify = bool(_v137.do_rectify) 02728 _v138 = _v124.roi_box_pose 02729 _v139 = _v138.header 02730 start = end 02731 end += 4 02732 (_v139.seq,) = _struct_I.unpack(str[start:end]) 02733 _v140 = _v139.stamp 02734 _x = _v140 02735 start = end 02736 end += 8 02737 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02738 start = end 02739 end += 4 02740 (length,) = _struct_I.unpack(str[start:end]) 02741 start = end 02742 end += length 02743 _v139.frame_id = str[start:end] 02744 _v141 = _v138.pose 02745 _v142 = _v141.position 02746 _x = _v142 02747 start = end 02748 end += 24 02749 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 02750 _v143 = _v141.orientation 02751 _x = _v143 02752 start = end 02753 end += 32 02754 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 02755 _v144 = _v124.roi_box_dims 02756 _x = _v144 02757 start = end 02758 end += 24 02759 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 02760 start = end 02761 end += 4 02762 (length,) = _struct_I.unpack(str[start:end]) 02763 start = end 02764 end += length 02765 val1.collision_name = str[start:end] 02766 self.grasp.moved_obstacles.append(val1) 02767 return self 02768 except struct.error as e: 02769 raise roslib.message.DeserializationError(e) #most likely buffer underfill 02770 02771 _struct_I = roslib.message.struct_I 02772 _struct_IBI = struct.Struct("<IBI") 02773 _struct_6IB3I = struct.Struct("<6IB3I") 02774 _struct_B = struct.Struct("<B") 02775 _struct_12d = struct.Struct("<12d") 02776 _struct_7df = struct.Struct("<7df") 02777 _struct_f = struct.Struct("<f") 02778 _struct_i = struct.Struct("<i") 02779 _struct_BI = struct.Struct("<BI") 02780 _struct_10d = struct.Struct("<10d") 02781 _struct_3f = struct.Struct("<3f") 02782 _struct_3I = struct.Struct("<3I") 02783 _struct_8dB2f = struct.Struct("<8dB2f") 02784 _struct_9d = struct.Struct("<9d") 02785 _struct_B2I = struct.Struct("<B2I") 02786 _struct_4d = struct.Struct("<4d") 02787 _struct_2I = struct.Struct("<2I") 02788 _struct_4IB = struct.Struct("<4IB") 02789 _struct_3d = struct.Struct("<3d")