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