00001 """autogenerated by genmsg_py from GraspableObject.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import sensor_msgs.msg
00006 import std_msgs.msg
00007 import geometry_msgs.msg
00008 import object_manipulation_msgs.msg
00009 import household_objects_database_msgs.msg
00010
00011 class GraspableObject(roslib.message.Message):
00012 _md5sum = "9df73c592d4de91f750a00a6702caa0d"
00013 _type = "object_manipulation_msgs/GraspableObject"
00014 _has_header = False
00015 _full_text = """# an object that the object_manipulator can work on
00016
00017 # a graspable object can be represented in multiple ways. This message
00018 # can contain all of them. Which one is actually used is up to the receiver
00019 # of this message. When adding new representations, one must be careful that
00020 # they have reasonable lightweight defaults indicating that that particular
00021 # representation is not available.
00022
00023 # the tf frame to be used as a reference frame when combining information from
00024 # the different representations below
00025 string reference_frame_id
00026
00027 # potential recognition results from a database of models
00028 # all poses are relative to the object reference pose
00029 household_objects_database_msgs/DatabaseModelPose[] potential_models
00030
00031 # the point cloud itself
00032 sensor_msgs/PointCloud cluster
00033
00034 # a region of a PointCloud2 of interest
00035 object_manipulation_msgs/SceneRegion region
00036
00037
00038 ================================================================================
00039 MSG: household_objects_database_msgs/DatabaseModelPose
00040 # Informs that a specific model from the Model Database has been
00041 # identified at a certain location
00042
00043 # the database id of the model
00044 int32 model_id
00045
00046 # the pose that it can be found in
00047 geometry_msgs/PoseStamped pose
00048
00049 # a measure of the confidence level in this detection result
00050 float32 confidence
00051 ================================================================================
00052 MSG: geometry_msgs/PoseStamped
00053 # A Pose with reference coordinate frame and timestamp
00054 Header header
00055 Pose pose
00056
00057 ================================================================================
00058 MSG: std_msgs/Header
00059 # Standard metadata for higher-level stamped data types.
00060 # This is generally used to communicate timestamped data
00061 # in a particular coordinate frame.
00062 #
00063 # sequence ID: consecutively increasing ID
00064 uint32 seq
00065 #Two-integer timestamp that is expressed as:
00066 # * stamp.secs: seconds (stamp_secs) since epoch
00067 # * stamp.nsecs: nanoseconds since stamp_secs
00068 # time-handling sugar is provided by the client library
00069 time stamp
00070 #Frame this data is associated with
00071 # 0: no frame
00072 # 1: global frame
00073 string frame_id
00074
00075 ================================================================================
00076 MSG: geometry_msgs/Pose
00077 # A representation of pose in free space, composed of postion and orientation.
00078 Point position
00079 Quaternion orientation
00080
00081 ================================================================================
00082 MSG: geometry_msgs/Point
00083 # This contains the position of a point in free space
00084 float64 x
00085 float64 y
00086 float64 z
00087
00088 ================================================================================
00089 MSG: geometry_msgs/Quaternion
00090 # This represents an orientation in free space in quaternion form.
00091
00092 float64 x
00093 float64 y
00094 float64 z
00095 float64 w
00096
00097 ================================================================================
00098 MSG: sensor_msgs/PointCloud
00099 # This message holds a collection of 3d points, plus optional additional
00100 # information about each point.
00101
00102 # Time of sensor data acquisition, coordinate frame ID.
00103 Header header
00104
00105 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00106 # in the frame given in the header.
00107 geometry_msgs/Point32[] points
00108
00109 # Each channel should have the same number of elements as points array,
00110 # and the data in each channel should correspond 1:1 with each point.
00111 # Channel names in common practice are listed in ChannelFloat32.msg.
00112 ChannelFloat32[] channels
00113
00114 ================================================================================
00115 MSG: geometry_msgs/Point32
00116 # This contains the position of a point in free space(with 32 bits of precision).
00117 # It is recommeded to use Point wherever possible instead of Point32.
00118 #
00119 # This recommendation is to promote interoperability.
00120 #
00121 # This message is designed to take up less space when sending
00122 # lots of points at once, as in the case of a PointCloud.
00123
00124 float32 x
00125 float32 y
00126 float32 z
00127 ================================================================================
00128 MSG: sensor_msgs/ChannelFloat32
00129 # This message is used by the PointCloud message to hold optional data
00130 # associated with each point in the cloud. The length of the values
00131 # array should be the same as the length of the points array in the
00132 # PointCloud, and each value should be associated with the corresponding
00133 # point.
00134
00135 # Channel names in existing practice include:
00136 # "u", "v" - row and column (respectively) in the left stereo image.
00137 # This is opposite to usual conventions but remains for
00138 # historical reasons. The newer PointCloud2 message has no
00139 # such problem.
00140 # "rgb" - For point clouds produced by color stereo cameras. uint8
00141 # (R,G,B) values packed into the least significant 24 bits,
00142 # in order.
00143 # "intensity" - laser or pixel intensity.
00144 # "distance"
00145
00146 # The channel name should give semantics of the channel (e.g.
00147 # "intensity" instead of "value").
00148 string name
00149
00150 # The values array should be 1-1 with the elements of the associated
00151 # PointCloud.
00152 float32[] values
00153
00154 ================================================================================
00155 MSG: object_manipulation_msgs/SceneRegion
00156 # Point cloud
00157 sensor_msgs/PointCloud2 cloud
00158
00159 # Indices for the region of interest
00160 int32[] mask
00161
00162 # One of the corresponding 2D images, if applicable
00163 sensor_msgs/Image image
00164
00165 # The disparity image, if applicable
00166 sensor_msgs/Image disparity_image
00167
00168 # Camera info for the camera that took the image
00169 sensor_msgs/CameraInfo cam_info
00170
00171 ================================================================================
00172 MSG: sensor_msgs/PointCloud2
00173 # This message holds a collection of N-dimensional points, which may
00174 # contain additional information such as normals, intensity, etc. The
00175 # point data is stored as a binary blob, its layout described by the
00176 # contents of the "fields" array.
00177
00178 # The point cloud data may be organized 2d (image-like) or 1d
00179 # (unordered). Point clouds organized as 2d images may be produced by
00180 # camera depth sensors such as stereo or time-of-flight.
00181
00182 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00183 # points).
00184 Header header
00185
00186 # 2D structure of the point cloud. If the cloud is unordered, height is
00187 # 1 and width is the length of the point cloud.
00188 uint32 height
00189 uint32 width
00190
00191 # Describes the channels and their layout in the binary data blob.
00192 PointField[] fields
00193
00194 bool is_bigendian # Is this data bigendian?
00195 uint32 point_step # Length of a point in bytes
00196 uint32 row_step # Length of a row in bytes
00197 uint8[] data # Actual point data, size is (row_step*height)
00198
00199 bool is_dense # True if there are no invalid points
00200
00201 ================================================================================
00202 MSG: sensor_msgs/PointField
00203 # This message holds the description of one point entry in the
00204 # PointCloud2 message format.
00205 uint8 INT8 = 1
00206 uint8 UINT8 = 2
00207 uint8 INT16 = 3
00208 uint8 UINT16 = 4
00209 uint8 INT32 = 5
00210 uint8 UINT32 = 6
00211 uint8 FLOAT32 = 7
00212 uint8 FLOAT64 = 8
00213
00214 string name # Name of field
00215 uint32 offset # Offset from start of point struct
00216 uint8 datatype # Datatype enumeration, see above
00217 uint32 count # How many elements in the field
00218
00219 ================================================================================
00220 MSG: sensor_msgs/Image
00221 # This message contains an uncompressed image
00222 # (0, 0) is at top-left corner of image
00223 #
00224
00225 Header header # Header timestamp should be acquisition time of image
00226 # Header frame_id should be optical frame of camera
00227 # origin of frame should be optical center of cameara
00228 # +x should point to the right in the image
00229 # +y should point down in the image
00230 # +z should point into to plane of the image
00231 # If the frame_id here and the frame_id of the CameraInfo
00232 # message associated with the image conflict
00233 # the behavior is undefined
00234
00235 uint32 height # image height, that is, number of rows
00236 uint32 width # image width, that is, number of columns
00237
00238 # The legal values for encoding are in file src/image_encodings.cpp
00239 # If you want to standardize a new string format, join
00240 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00241
00242 string encoding # Encoding of pixels -- channel meaning, ordering, size
00243 # taken from the list of strings in src/image_encodings.cpp
00244
00245 uint8 is_bigendian # is this data bigendian?
00246 uint32 step # Full row length in bytes
00247 uint8[] data # actual matrix data, size is (step * rows)
00248
00249 ================================================================================
00250 MSG: sensor_msgs/CameraInfo
00251 # This message defines meta information for a camera. It should be in a
00252 # camera namespace on topic "camera_info" and accompanied by up to five
00253 # image topics named:
00254 #
00255 # image_raw - raw data from the camera driver, possibly Bayer encoded
00256 # image - monochrome, distorted
00257 # image_color - color, distorted
00258 # image_rect - monochrome, rectified
00259 # image_rect_color - color, rectified
00260 #
00261 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00262 # for producing the four processed image topics from image_raw and
00263 # camera_info. The meaning of the camera parameters are described in
00264 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00265 #
00266 # The image_geometry package provides a user-friendly interface to
00267 # common operations using this meta information. If you want to, e.g.,
00268 # project a 3d point into image coordinates, we strongly recommend
00269 # using image_geometry.
00270 #
00271 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00272 # zeroed out. In particular, clients may assume that K[0] == 0.0
00273 # indicates an uncalibrated camera.
00274
00275 #######################################################################
00276 # Image acquisition info #
00277 #######################################################################
00278
00279 # Time of image acquisition, camera coordinate frame ID
00280 Header header # Header timestamp should be acquisition time of image
00281 # Header frame_id should be optical frame of camera
00282 # origin of frame should be optical center of camera
00283 # +x should point to the right in the image
00284 # +y should point down in the image
00285 # +z should point into the plane of the image
00286
00287
00288 #######################################################################
00289 # Calibration Parameters #
00290 #######################################################################
00291 # These are fixed during camera calibration. Their values will be the #
00292 # same in all messages until the camera is recalibrated. Note that #
00293 # self-calibrating systems may "recalibrate" frequently. #
00294 # #
00295 # The internal parameters can be used to warp a raw (distorted) image #
00296 # to: #
00297 # 1. An undistorted image (requires D and K) #
00298 # 2. A rectified image (requires D, K, R) #
00299 # The projection matrix P projects 3D points into the rectified image.#
00300 #######################################################################
00301
00302 # The image dimensions with which the camera was calibrated. Normally
00303 # this will be the full camera resolution in pixels.
00304 uint32 height
00305 uint32 width
00306
00307 # The distortion model used. Supported models are listed in
00308 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00309 # simple model of radial and tangential distortion - is sufficent.
00310 string distortion_model
00311
00312 # The distortion parameters, size depending on the distortion model.
00313 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00314 float64[] D
00315
00316 # Intrinsic camera matrix for the raw (distorted) images.
00317 # [fx 0 cx]
00318 # K = [ 0 fy cy]
00319 # [ 0 0 1]
00320 # Projects 3D points in the camera coordinate frame to 2D pixel
00321 # coordinates using the focal lengths (fx, fy) and principal point
00322 # (cx, cy).
00323 float64[9] K # 3x3 row-major matrix
00324
00325 # Rectification matrix (stereo cameras only)
00326 # A rotation matrix aligning the camera coordinate system to the ideal
00327 # stereo image plane so that epipolar lines in both stereo images are
00328 # parallel.
00329 float64[9] R # 3x3 row-major matrix
00330
00331 # Projection/camera matrix
00332 # [fx' 0 cx' Tx]
00333 # P = [ 0 fy' cy' Ty]
00334 # [ 0 0 1 0]
00335 # By convention, this matrix specifies the intrinsic (camera) matrix
00336 # of the processed (rectified) image. That is, the left 3x3 portion
00337 # is the normal camera intrinsic matrix for the rectified image.
00338 # It projects 3D points in the camera coordinate frame to 2D pixel
00339 # coordinates using the focal lengths (fx', fy') and principal point
00340 # (cx', cy') - these may differ from the values in K.
00341 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00342 # also have R = the identity and P[1:3,1:3] = K.
00343 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00344 # position of the optical center of the second camera in the first
00345 # camera's frame. We assume Tz = 0 so both cameras are in the same
00346 # stereo image plane. The first camera always has Tx = Ty = 0. For
00347 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00348 # Tx = -fx' * B, where B is the baseline between the cameras.
00349 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00350 # the rectified image is given by:
00351 # [u v w]' = P * [X Y Z 1]'
00352 # x = u / w
00353 # y = v / w
00354 # This holds for both images of a stereo pair.
00355 float64[12] P # 3x4 row-major matrix
00356
00357
00358 #######################################################################
00359 # Operational Parameters #
00360 #######################################################################
00361 # These define the image region actually captured by the camera #
00362 # driver. Although they affect the geometry of the output image, they #
00363 # may be changed freely without recalibrating the camera. #
00364 #######################################################################
00365
00366 # Binning refers here to any camera setting which combines rectangular
00367 # neighborhoods of pixels into larger "super-pixels." It reduces the
00368 # resolution of the output image to
00369 # (width / binning_x) x (height / binning_y).
00370 # The default values binning_x = binning_y = 0 is considered the same
00371 # as binning_x = binning_y = 1 (no subsampling).
00372 uint32 binning_x
00373 uint32 binning_y
00374
00375 # Region of interest (subwindow of full camera resolution), given in
00376 # full resolution (unbinned) image coordinates. A particular ROI
00377 # always denotes the same window of pixels on the camera sensor,
00378 # regardless of binning settings.
00379 # The default setting of roi (all values 0) is considered the same as
00380 # full resolution (roi.width = width, roi.height = height).
00381 RegionOfInterest roi
00382
00383 ================================================================================
00384 MSG: sensor_msgs/RegionOfInterest
00385 # This message is used to specify a region of interest within an image.
00386 #
00387 # When used to specify the ROI setting of the camera when the image was
00388 # taken, the height and width fields should either match the height and
00389 # width fields for the associated image; or height = width = 0
00390 # indicates that the full resolution image was captured.
00391
00392 uint32 x_offset # Leftmost pixel of the ROI
00393 # (0 if the ROI includes the left edge of the image)
00394 uint32 y_offset # Topmost pixel of the ROI
00395 # (0 if the ROI includes the top edge of the image)
00396 uint32 height # Height of ROI
00397 uint32 width # Width of ROI
00398
00399 # True if a distinct rectified ROI should be calculated from the "raw"
00400 # ROI in this message. Typically this should be False if the full image
00401 # is captured (ROI not used), and True if a subwindow is captured (ROI
00402 # used).
00403 bool do_rectify
00404
00405 """
00406 __slots__ = ['reference_frame_id','potential_models','cluster','region']
00407 _slot_types = ['string','household_objects_database_msgs/DatabaseModelPose[]','sensor_msgs/PointCloud','object_manipulation_msgs/SceneRegion']
00408
00409 def __init__(self, *args, **kwds):
00410 """
00411 Constructor. Any message fields that are implicitly/explicitly
00412 set to None will be assigned a default value. The recommend
00413 use is keyword arguments as this is more robust to future message
00414 changes. You cannot mix in-order arguments and keyword arguments.
00415
00416 The available fields are:
00417 reference_frame_id,potential_models,cluster,region
00418
00419 @param args: complete set of field values, in .msg order
00420 @param kwds: use keyword arguments corresponding to message field names
00421 to set specific fields.
00422 """
00423 if args or kwds:
00424 super(GraspableObject, self).__init__(*args, **kwds)
00425 #message fields cannot be None, assign default values for those that are
00426 if self.reference_frame_id is None:
00427 self.reference_frame_id = ''
00428 if self.potential_models is None:
00429 self.potential_models = []
00430 if self.cluster is None:
00431 self.cluster = sensor_msgs.msg.PointCloud()
00432 if self.region is None:
00433 self.region = object_manipulation_msgs.msg.SceneRegion()
00434 else:
00435 self.reference_frame_id = ''
00436 self.potential_models = []
00437 self.cluster = sensor_msgs.msg.PointCloud()
00438 self.region = object_manipulation_msgs.msg.SceneRegion()
00439
00440 def _get_types(self):
00441 """
00442 internal API method
00443 """
00444 return self._slot_types
00445
00446 def serialize(self, buff):
00447 """
00448 serialize message into buffer
00449 @param buff: buffer
00450 @type buff: StringIO
00451 """
00452 try:
00453 _x = self.reference_frame_id
00454 length = len(_x)
00455 buff.write(struct.pack('<I%ss'%length, length, _x))
00456 length = len(self.potential_models)
00457 buff.write(_struct_I.pack(length))
00458 for val1 in self.potential_models:
00459 buff.write(_struct_i.pack(val1.model_id))
00460 _v1 = val1.pose
00461 _v2 = _v1.header
00462 buff.write(_struct_I.pack(_v2.seq))
00463 _v3 = _v2.stamp
00464 _x = _v3
00465 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00466 _x = _v2.frame_id
00467 length = len(_x)
00468 buff.write(struct.pack('<I%ss'%length, length, _x))
00469 _v4 = _v1.pose
00470 _v5 = _v4.position
00471 _x = _v5
00472 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00473 _v6 = _v4.orientation
00474 _x = _v6
00475 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00476 buff.write(_struct_f.pack(val1.confidence))
00477 _x = self
00478 buff.write(_struct_3I.pack(_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs))
00479 _x = self.cluster.header.frame_id
00480 length = len(_x)
00481 buff.write(struct.pack('<I%ss'%length, length, _x))
00482 length = len(self.cluster.points)
00483 buff.write(_struct_I.pack(length))
00484 for val1 in self.cluster.points:
00485 _x = val1
00486 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00487 length = len(self.cluster.channels)
00488 buff.write(_struct_I.pack(length))
00489 for val1 in self.cluster.channels:
00490 _x = val1.name
00491 length = len(_x)
00492 buff.write(struct.pack('<I%ss'%length, length, _x))
00493 length = len(val1.values)
00494 buff.write(_struct_I.pack(length))
00495 pattern = '<%sf'%length
00496 buff.write(struct.pack(pattern, *val1.values))
00497 _x = self
00498 buff.write(_struct_3I.pack(_x.region.cloud.header.seq, _x.region.cloud.header.stamp.secs, _x.region.cloud.header.stamp.nsecs))
00499 _x = self.region.cloud.header.frame_id
00500 length = len(_x)
00501 buff.write(struct.pack('<I%ss'%length, length, _x))
00502 _x = self
00503 buff.write(_struct_2I.pack(_x.region.cloud.height, _x.region.cloud.width))
00504 length = len(self.region.cloud.fields)
00505 buff.write(_struct_I.pack(length))
00506 for val1 in self.region.cloud.fields:
00507 _x = val1.name
00508 length = len(_x)
00509 buff.write(struct.pack('<I%ss'%length, length, _x))
00510 _x = val1
00511 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00512 _x = self
00513 buff.write(_struct_B2I.pack(_x.region.cloud.is_bigendian, _x.region.cloud.point_step, _x.region.cloud.row_step))
00514 _x = self.region.cloud.data
00515 length = len(_x)
00516 # - if encoded as a list instead, serialize as bytes instead of string
00517 if type(_x) in [list, tuple]:
00518 buff.write(struct.pack('<I%sB'%length, length, *_x))
00519 else:
00520 buff.write(struct.pack('<I%ss'%length, length, _x))
00521 buff.write(_struct_B.pack(self.region.cloud.is_dense))
00522 length = len(self.region.mask)
00523 buff.write(_struct_I.pack(length))
00524 pattern = '<%si'%length
00525 buff.write(struct.pack(pattern, *self.region.mask))
00526 _x = self
00527 buff.write(_struct_3I.pack(_x.region.image.header.seq, _x.region.image.header.stamp.secs, _x.region.image.header.stamp.nsecs))
00528 _x = self.region.image.header.frame_id
00529 length = len(_x)
00530 buff.write(struct.pack('<I%ss'%length, length, _x))
00531 _x = self
00532 buff.write(_struct_2I.pack(_x.region.image.height, _x.region.image.width))
00533 _x = self.region.image.encoding
00534 length = len(_x)
00535 buff.write(struct.pack('<I%ss'%length, length, _x))
00536 _x = self
00537 buff.write(_struct_BI.pack(_x.region.image.is_bigendian, _x.region.image.step))
00538 _x = self.region.image.data
00539 length = len(_x)
00540 # - if encoded as a list instead, serialize as bytes instead of string
00541 if type(_x) in [list, tuple]:
00542 buff.write(struct.pack('<I%sB'%length, length, *_x))
00543 else:
00544 buff.write(struct.pack('<I%ss'%length, length, _x))
00545 _x = self
00546 buff.write(_struct_3I.pack(_x.region.disparity_image.header.seq, _x.region.disparity_image.header.stamp.secs, _x.region.disparity_image.header.stamp.nsecs))
00547 _x = self.region.disparity_image.header.frame_id
00548 length = len(_x)
00549 buff.write(struct.pack('<I%ss'%length, length, _x))
00550 _x = self
00551 buff.write(_struct_2I.pack(_x.region.disparity_image.height, _x.region.disparity_image.width))
00552 _x = self.region.disparity_image.encoding
00553 length = len(_x)
00554 buff.write(struct.pack('<I%ss'%length, length, _x))
00555 _x = self
00556 buff.write(_struct_BI.pack(_x.region.disparity_image.is_bigendian, _x.region.disparity_image.step))
00557 _x = self.region.disparity_image.data
00558 length = len(_x)
00559 # - if encoded as a list instead, serialize as bytes instead of string
00560 if type(_x) in [list, tuple]:
00561 buff.write(struct.pack('<I%sB'%length, length, *_x))
00562 else:
00563 buff.write(struct.pack('<I%ss'%length, length, _x))
00564 _x = self
00565 buff.write(_struct_3I.pack(_x.region.cam_info.header.seq, _x.region.cam_info.header.stamp.secs, _x.region.cam_info.header.stamp.nsecs))
00566 _x = self.region.cam_info.header.frame_id
00567 length = len(_x)
00568 buff.write(struct.pack('<I%ss'%length, length, _x))
00569 _x = self
00570 buff.write(_struct_2I.pack(_x.region.cam_info.height, _x.region.cam_info.width))
00571 _x = self.region.cam_info.distortion_model
00572 length = len(_x)
00573 buff.write(struct.pack('<I%ss'%length, length, _x))
00574 length = len(self.region.cam_info.D)
00575 buff.write(_struct_I.pack(length))
00576 pattern = '<%sd'%length
00577 buff.write(struct.pack(pattern, *self.region.cam_info.D))
00578 buff.write(_struct_9d.pack(*self.region.cam_info.K))
00579 buff.write(_struct_9d.pack(*self.region.cam_info.R))
00580 buff.write(_struct_12d.pack(*self.region.cam_info.P))
00581 _x = self
00582 buff.write(_struct_6IB.pack(_x.region.cam_info.binning_x, _x.region.cam_info.binning_y, _x.region.cam_info.roi.x_offset, _x.region.cam_info.roi.y_offset, _x.region.cam_info.roi.height, _x.region.cam_info.roi.width, _x.region.cam_info.roi.do_rectify))
00583 except struct.error, se: self._check_types(se)
00584 except TypeError, te: self._check_types(te)
00585
00586 def deserialize(self, str):
00587 """
00588 unpack serialized message in str into this message instance
00589 @param str: byte array of serialized message
00590 @type str: str
00591 """
00592 try:
00593 if self.cluster is None:
00594 self.cluster = sensor_msgs.msg.PointCloud()
00595 if self.region is None:
00596 self.region = object_manipulation_msgs.msg.SceneRegion()
00597 end = 0
00598 start = end
00599 end += 4
00600 (length,) = _struct_I.unpack(str[start:end])
00601 start = end
00602 end += length
00603 self.reference_frame_id = str[start:end]
00604 start = end
00605 end += 4
00606 (length,) = _struct_I.unpack(str[start:end])
00607 self.potential_models = []
00608 for i in xrange(0, length):
00609 val1 = household_objects_database_msgs.msg.DatabaseModelPose()
00610 start = end
00611 end += 4
00612 (val1.model_id,) = _struct_i.unpack(str[start:end])
00613 _v7 = val1.pose
00614 _v8 = _v7.header
00615 start = end
00616 end += 4
00617 (_v8.seq,) = _struct_I.unpack(str[start:end])
00618 _v9 = _v8.stamp
00619 _x = _v9
00620 start = end
00621 end += 8
00622 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00623 start = end
00624 end += 4
00625 (length,) = _struct_I.unpack(str[start:end])
00626 start = end
00627 end += length
00628 _v8.frame_id = str[start:end]
00629 _v10 = _v7.pose
00630 _v11 = _v10.position
00631 _x = _v11
00632 start = end
00633 end += 24
00634 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00635 _v12 = _v10.orientation
00636 _x = _v12
00637 start = end
00638 end += 32
00639 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00640 start = end
00641 end += 4
00642 (val1.confidence,) = _struct_f.unpack(str[start:end])
00643 self.potential_models.append(val1)
00644 _x = self
00645 start = end
00646 end += 12
00647 (_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00648 start = end
00649 end += 4
00650 (length,) = _struct_I.unpack(str[start:end])
00651 start = end
00652 end += length
00653 self.cluster.header.frame_id = str[start:end]
00654 start = end
00655 end += 4
00656 (length,) = _struct_I.unpack(str[start:end])
00657 self.cluster.points = []
00658 for i in xrange(0, length):
00659 val1 = geometry_msgs.msg.Point32()
00660 _x = val1
00661 start = end
00662 end += 12
00663 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00664 self.cluster.points.append(val1)
00665 start = end
00666 end += 4
00667 (length,) = _struct_I.unpack(str[start:end])
00668 self.cluster.channels = []
00669 for i in xrange(0, length):
00670 val1 = sensor_msgs.msg.ChannelFloat32()
00671 start = end
00672 end += 4
00673 (length,) = _struct_I.unpack(str[start:end])
00674 start = end
00675 end += length
00676 val1.name = str[start:end]
00677 start = end
00678 end += 4
00679 (length,) = _struct_I.unpack(str[start:end])
00680 pattern = '<%sf'%length
00681 start = end
00682 end += struct.calcsize(pattern)
00683 val1.values = struct.unpack(pattern, str[start:end])
00684 self.cluster.channels.append(val1)
00685 _x = self
00686 start = end
00687 end += 12
00688 (_x.region.cloud.header.seq, _x.region.cloud.header.stamp.secs, _x.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00689 start = end
00690 end += 4
00691 (length,) = _struct_I.unpack(str[start:end])
00692 start = end
00693 end += length
00694 self.region.cloud.header.frame_id = str[start:end]
00695 _x = self
00696 start = end
00697 end += 8
00698 (_x.region.cloud.height, _x.region.cloud.width,) = _struct_2I.unpack(str[start:end])
00699 start = end
00700 end += 4
00701 (length,) = _struct_I.unpack(str[start:end])
00702 self.region.cloud.fields = []
00703 for i in xrange(0, length):
00704 val1 = sensor_msgs.msg.PointField()
00705 start = end
00706 end += 4
00707 (length,) = _struct_I.unpack(str[start:end])
00708 start = end
00709 end += length
00710 val1.name = str[start:end]
00711 _x = val1
00712 start = end
00713 end += 9
00714 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00715 self.region.cloud.fields.append(val1)
00716 _x = self
00717 start = end
00718 end += 9
00719 (_x.region.cloud.is_bigendian, _x.region.cloud.point_step, _x.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00720 self.region.cloud.is_bigendian = bool(self.region.cloud.is_bigendian)
00721 start = end
00722 end += 4
00723 (length,) = _struct_I.unpack(str[start:end])
00724 start = end
00725 end += length
00726 self.region.cloud.data = str[start:end]
00727 start = end
00728 end += 1
00729 (self.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
00730 self.region.cloud.is_dense = bool(self.region.cloud.is_dense)
00731 start = end
00732 end += 4
00733 (length,) = _struct_I.unpack(str[start:end])
00734 pattern = '<%si'%length
00735 start = end
00736 end += struct.calcsize(pattern)
00737 self.region.mask = struct.unpack(pattern, str[start:end])
00738 _x = self
00739 start = end
00740 end += 12
00741 (_x.region.image.header.seq, _x.region.image.header.stamp.secs, _x.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00742 start = end
00743 end += 4
00744 (length,) = _struct_I.unpack(str[start:end])
00745 start = end
00746 end += length
00747 self.region.image.header.frame_id = str[start:end]
00748 _x = self
00749 start = end
00750 end += 8
00751 (_x.region.image.height, _x.region.image.width,) = _struct_2I.unpack(str[start:end])
00752 start = end
00753 end += 4
00754 (length,) = _struct_I.unpack(str[start:end])
00755 start = end
00756 end += length
00757 self.region.image.encoding = str[start:end]
00758 _x = self
00759 start = end
00760 end += 5
00761 (_x.region.image.is_bigendian, _x.region.image.step,) = _struct_BI.unpack(str[start:end])
00762 start = end
00763 end += 4
00764 (length,) = _struct_I.unpack(str[start:end])
00765 start = end
00766 end += length
00767 self.region.image.data = str[start:end]
00768 _x = self
00769 start = end
00770 end += 12
00771 (_x.region.disparity_image.header.seq, _x.region.disparity_image.header.stamp.secs, _x.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00772 start = end
00773 end += 4
00774 (length,) = _struct_I.unpack(str[start:end])
00775 start = end
00776 end += length
00777 self.region.disparity_image.header.frame_id = str[start:end]
00778 _x = self
00779 start = end
00780 end += 8
00781 (_x.region.disparity_image.height, _x.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
00782 start = end
00783 end += 4
00784 (length,) = _struct_I.unpack(str[start:end])
00785 start = end
00786 end += length
00787 self.region.disparity_image.encoding = str[start:end]
00788 _x = self
00789 start = end
00790 end += 5
00791 (_x.region.disparity_image.is_bigendian, _x.region.disparity_image.step,) = _struct_BI.unpack(str[start:end])
00792 start = end
00793 end += 4
00794 (length,) = _struct_I.unpack(str[start:end])
00795 start = end
00796 end += length
00797 self.region.disparity_image.data = str[start:end]
00798 _x = self
00799 start = end
00800 end += 12
00801 (_x.region.cam_info.header.seq, _x.region.cam_info.header.stamp.secs, _x.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00802 start = end
00803 end += 4
00804 (length,) = _struct_I.unpack(str[start:end])
00805 start = end
00806 end += length
00807 self.region.cam_info.header.frame_id = str[start:end]
00808 _x = self
00809 start = end
00810 end += 8
00811 (_x.region.cam_info.height, _x.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
00812 start = end
00813 end += 4
00814 (length,) = _struct_I.unpack(str[start:end])
00815 start = end
00816 end += length
00817 self.region.cam_info.distortion_model = str[start:end]
00818 start = end
00819 end += 4
00820 (length,) = _struct_I.unpack(str[start:end])
00821 pattern = '<%sd'%length
00822 start = end
00823 end += struct.calcsize(pattern)
00824 self.region.cam_info.D = struct.unpack(pattern, str[start:end])
00825 start = end
00826 end += 72
00827 self.region.cam_info.K = _struct_9d.unpack(str[start:end])
00828 start = end
00829 end += 72
00830 self.region.cam_info.R = _struct_9d.unpack(str[start:end])
00831 start = end
00832 end += 96
00833 self.region.cam_info.P = _struct_12d.unpack(str[start:end])
00834 _x = self
00835 start = end
00836 end += 25
00837 (_x.region.cam_info.binning_x, _x.region.cam_info.binning_y, _x.region.cam_info.roi.x_offset, _x.region.cam_info.roi.y_offset, _x.region.cam_info.roi.height, _x.region.cam_info.roi.width, _x.region.cam_info.roi.do_rectify,) = _struct_6IB.unpack(str[start:end])
00838 self.region.cam_info.roi.do_rectify = bool(self.region.cam_info.roi.do_rectify)
00839 return self
00840 except struct.error, e:
00841 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00842
00843
00844 def serialize_numpy(self, buff, numpy):
00845 """
00846 serialize message with numpy array types into buffer
00847 @param buff: buffer
00848 @type buff: StringIO
00849 @param numpy: numpy python module
00850 @type numpy module
00851 """
00852 try:
00853 _x = self.reference_frame_id
00854 length = len(_x)
00855 buff.write(struct.pack('<I%ss'%length, length, _x))
00856 length = len(self.potential_models)
00857 buff.write(_struct_I.pack(length))
00858 for val1 in self.potential_models:
00859 buff.write(_struct_i.pack(val1.model_id))
00860 _v13 = val1.pose
00861 _v14 = _v13.header
00862 buff.write(_struct_I.pack(_v14.seq))
00863 _v15 = _v14.stamp
00864 _x = _v15
00865 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00866 _x = _v14.frame_id
00867 length = len(_x)
00868 buff.write(struct.pack('<I%ss'%length, length, _x))
00869 _v16 = _v13.pose
00870 _v17 = _v16.position
00871 _x = _v17
00872 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00873 _v18 = _v16.orientation
00874 _x = _v18
00875 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00876 buff.write(_struct_f.pack(val1.confidence))
00877 _x = self
00878 buff.write(_struct_3I.pack(_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs))
00879 _x = self.cluster.header.frame_id
00880 length = len(_x)
00881 buff.write(struct.pack('<I%ss'%length, length, _x))
00882 length = len(self.cluster.points)
00883 buff.write(_struct_I.pack(length))
00884 for val1 in self.cluster.points:
00885 _x = val1
00886 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00887 length = len(self.cluster.channels)
00888 buff.write(_struct_I.pack(length))
00889 for val1 in self.cluster.channels:
00890 _x = val1.name
00891 length = len(_x)
00892 buff.write(struct.pack('<I%ss'%length, length, _x))
00893 length = len(val1.values)
00894 buff.write(_struct_I.pack(length))
00895 pattern = '<%sf'%length
00896 buff.write(val1.values.tostring())
00897 _x = self
00898 buff.write(_struct_3I.pack(_x.region.cloud.header.seq, _x.region.cloud.header.stamp.secs, _x.region.cloud.header.stamp.nsecs))
00899 _x = self.region.cloud.header.frame_id
00900 length = len(_x)
00901 buff.write(struct.pack('<I%ss'%length, length, _x))
00902 _x = self
00903 buff.write(_struct_2I.pack(_x.region.cloud.height, _x.region.cloud.width))
00904 length = len(self.region.cloud.fields)
00905 buff.write(_struct_I.pack(length))
00906 for val1 in self.region.cloud.fields:
00907 _x = val1.name
00908 length = len(_x)
00909 buff.write(struct.pack('<I%ss'%length, length, _x))
00910 _x = val1
00911 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00912 _x = self
00913 buff.write(_struct_B2I.pack(_x.region.cloud.is_bigendian, _x.region.cloud.point_step, _x.region.cloud.row_step))
00914 _x = self.region.cloud.data
00915 length = len(_x)
00916 # - if encoded as a list instead, serialize as bytes instead of string
00917 if type(_x) in [list, tuple]:
00918 buff.write(struct.pack('<I%sB'%length, length, *_x))
00919 else:
00920 buff.write(struct.pack('<I%ss'%length, length, _x))
00921 buff.write(_struct_B.pack(self.region.cloud.is_dense))
00922 length = len(self.region.mask)
00923 buff.write(_struct_I.pack(length))
00924 pattern = '<%si'%length
00925 buff.write(self.region.mask.tostring())
00926 _x = self
00927 buff.write(_struct_3I.pack(_x.region.image.header.seq, _x.region.image.header.stamp.secs, _x.region.image.header.stamp.nsecs))
00928 _x = self.region.image.header.frame_id
00929 length = len(_x)
00930 buff.write(struct.pack('<I%ss'%length, length, _x))
00931 _x = self
00932 buff.write(_struct_2I.pack(_x.region.image.height, _x.region.image.width))
00933 _x = self.region.image.encoding
00934 length = len(_x)
00935 buff.write(struct.pack('<I%ss'%length, length, _x))
00936 _x = self
00937 buff.write(_struct_BI.pack(_x.region.image.is_bigendian, _x.region.image.step))
00938 _x = self.region.image.data
00939 length = len(_x)
00940 # - if encoded as a list instead, serialize as bytes instead of string
00941 if type(_x) in [list, tuple]:
00942 buff.write(struct.pack('<I%sB'%length, length, *_x))
00943 else:
00944 buff.write(struct.pack('<I%ss'%length, length, _x))
00945 _x = self
00946 buff.write(_struct_3I.pack(_x.region.disparity_image.header.seq, _x.region.disparity_image.header.stamp.secs, _x.region.disparity_image.header.stamp.nsecs))
00947 _x = self.region.disparity_image.header.frame_id
00948 length = len(_x)
00949 buff.write(struct.pack('<I%ss'%length, length, _x))
00950 _x = self
00951 buff.write(_struct_2I.pack(_x.region.disparity_image.height, _x.region.disparity_image.width))
00952 _x = self.region.disparity_image.encoding
00953 length = len(_x)
00954 buff.write(struct.pack('<I%ss'%length, length, _x))
00955 _x = self
00956 buff.write(_struct_BI.pack(_x.region.disparity_image.is_bigendian, _x.region.disparity_image.step))
00957 _x = self.region.disparity_image.data
00958 length = len(_x)
00959 # - if encoded as a list instead, serialize as bytes instead of string
00960 if type(_x) in [list, tuple]:
00961 buff.write(struct.pack('<I%sB'%length, length, *_x))
00962 else:
00963 buff.write(struct.pack('<I%ss'%length, length, _x))
00964 _x = self
00965 buff.write(_struct_3I.pack(_x.region.cam_info.header.seq, _x.region.cam_info.header.stamp.secs, _x.region.cam_info.header.stamp.nsecs))
00966 _x = self.region.cam_info.header.frame_id
00967 length = len(_x)
00968 buff.write(struct.pack('<I%ss'%length, length, _x))
00969 _x = self
00970 buff.write(_struct_2I.pack(_x.region.cam_info.height, _x.region.cam_info.width))
00971 _x = self.region.cam_info.distortion_model
00972 length = len(_x)
00973 buff.write(struct.pack('<I%ss'%length, length, _x))
00974 length = len(self.region.cam_info.D)
00975 buff.write(_struct_I.pack(length))
00976 pattern = '<%sd'%length
00977 buff.write(self.region.cam_info.D.tostring())
00978 buff.write(self.region.cam_info.K.tostring())
00979 buff.write(self.region.cam_info.R.tostring())
00980 buff.write(self.region.cam_info.P.tostring())
00981 _x = self
00982 buff.write(_struct_6IB.pack(_x.region.cam_info.binning_x, _x.region.cam_info.binning_y, _x.region.cam_info.roi.x_offset, _x.region.cam_info.roi.y_offset, _x.region.cam_info.roi.height, _x.region.cam_info.roi.width, _x.region.cam_info.roi.do_rectify))
00983 except struct.error, se: self._check_types(se)
00984 except TypeError, te: self._check_types(te)
00985
00986 def deserialize_numpy(self, str, numpy):
00987 """
00988 unpack serialized message in str into this message instance using numpy for array types
00989 @param str: byte array of serialized message
00990 @type str: str
00991 @param numpy: numpy python module
00992 @type numpy: module
00993 """
00994 try:
00995 if self.cluster is None:
00996 self.cluster = sensor_msgs.msg.PointCloud()
00997 if self.region is None:
00998 self.region = object_manipulation_msgs.msg.SceneRegion()
00999 end = 0
01000 start = end
01001 end += 4
01002 (length,) = _struct_I.unpack(str[start:end])
01003 start = end
01004 end += length
01005 self.reference_frame_id = str[start:end]
01006 start = end
01007 end += 4
01008 (length,) = _struct_I.unpack(str[start:end])
01009 self.potential_models = []
01010 for i in xrange(0, length):
01011 val1 = household_objects_database_msgs.msg.DatabaseModelPose()
01012 start = end
01013 end += 4
01014 (val1.model_id,) = _struct_i.unpack(str[start:end])
01015 _v19 = val1.pose
01016 _v20 = _v19.header
01017 start = end
01018 end += 4
01019 (_v20.seq,) = _struct_I.unpack(str[start:end])
01020 _v21 = _v20.stamp
01021 _x = _v21
01022 start = end
01023 end += 8
01024 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01025 start = end
01026 end += 4
01027 (length,) = _struct_I.unpack(str[start:end])
01028 start = end
01029 end += length
01030 _v20.frame_id = str[start:end]
01031 _v22 = _v19.pose
01032 _v23 = _v22.position
01033 _x = _v23
01034 start = end
01035 end += 24
01036 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01037 _v24 = _v22.orientation
01038 _x = _v24
01039 start = end
01040 end += 32
01041 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01042 start = end
01043 end += 4
01044 (val1.confidence,) = _struct_f.unpack(str[start:end])
01045 self.potential_models.append(val1)
01046 _x = self
01047 start = end
01048 end += 12
01049 (_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01050 start = end
01051 end += 4
01052 (length,) = _struct_I.unpack(str[start:end])
01053 start = end
01054 end += length
01055 self.cluster.header.frame_id = str[start:end]
01056 start = end
01057 end += 4
01058 (length,) = _struct_I.unpack(str[start:end])
01059 self.cluster.points = []
01060 for i in xrange(0, length):
01061 val1 = geometry_msgs.msg.Point32()
01062 _x = val1
01063 start = end
01064 end += 12
01065 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01066 self.cluster.points.append(val1)
01067 start = end
01068 end += 4
01069 (length,) = _struct_I.unpack(str[start:end])
01070 self.cluster.channels = []
01071 for i in xrange(0, length):
01072 val1 = sensor_msgs.msg.ChannelFloat32()
01073 start = end
01074 end += 4
01075 (length,) = _struct_I.unpack(str[start:end])
01076 start = end
01077 end += length
01078 val1.name = str[start:end]
01079 start = end
01080 end += 4
01081 (length,) = _struct_I.unpack(str[start:end])
01082 pattern = '<%sf'%length
01083 start = end
01084 end += struct.calcsize(pattern)
01085 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01086 self.cluster.channels.append(val1)
01087 _x = self
01088 start = end
01089 end += 12
01090 (_x.region.cloud.header.seq, _x.region.cloud.header.stamp.secs, _x.region.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01091 start = end
01092 end += 4
01093 (length,) = _struct_I.unpack(str[start:end])
01094 start = end
01095 end += length
01096 self.region.cloud.header.frame_id = str[start:end]
01097 _x = self
01098 start = end
01099 end += 8
01100 (_x.region.cloud.height, _x.region.cloud.width,) = _struct_2I.unpack(str[start:end])
01101 start = end
01102 end += 4
01103 (length,) = _struct_I.unpack(str[start:end])
01104 self.region.cloud.fields = []
01105 for i in xrange(0, length):
01106 val1 = sensor_msgs.msg.PointField()
01107 start = end
01108 end += 4
01109 (length,) = _struct_I.unpack(str[start:end])
01110 start = end
01111 end += length
01112 val1.name = str[start:end]
01113 _x = val1
01114 start = end
01115 end += 9
01116 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01117 self.region.cloud.fields.append(val1)
01118 _x = self
01119 start = end
01120 end += 9
01121 (_x.region.cloud.is_bigendian, _x.region.cloud.point_step, _x.region.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01122 self.region.cloud.is_bigendian = bool(self.region.cloud.is_bigendian)
01123 start = end
01124 end += 4
01125 (length,) = _struct_I.unpack(str[start:end])
01126 start = end
01127 end += length
01128 self.region.cloud.data = str[start:end]
01129 start = end
01130 end += 1
01131 (self.region.cloud.is_dense,) = _struct_B.unpack(str[start:end])
01132 self.region.cloud.is_dense = bool(self.region.cloud.is_dense)
01133 start = end
01134 end += 4
01135 (length,) = _struct_I.unpack(str[start:end])
01136 pattern = '<%si'%length
01137 start = end
01138 end += struct.calcsize(pattern)
01139 self.region.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01140 _x = self
01141 start = end
01142 end += 12
01143 (_x.region.image.header.seq, _x.region.image.header.stamp.secs, _x.region.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01144 start = end
01145 end += 4
01146 (length,) = _struct_I.unpack(str[start:end])
01147 start = end
01148 end += length
01149 self.region.image.header.frame_id = str[start:end]
01150 _x = self
01151 start = end
01152 end += 8
01153 (_x.region.image.height, _x.region.image.width,) = _struct_2I.unpack(str[start:end])
01154 start = end
01155 end += 4
01156 (length,) = _struct_I.unpack(str[start:end])
01157 start = end
01158 end += length
01159 self.region.image.encoding = str[start:end]
01160 _x = self
01161 start = end
01162 end += 5
01163 (_x.region.image.is_bigendian, _x.region.image.step,) = _struct_BI.unpack(str[start:end])
01164 start = end
01165 end += 4
01166 (length,) = _struct_I.unpack(str[start:end])
01167 start = end
01168 end += length
01169 self.region.image.data = str[start:end]
01170 _x = self
01171 start = end
01172 end += 12
01173 (_x.region.disparity_image.header.seq, _x.region.disparity_image.header.stamp.secs, _x.region.disparity_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01174 start = end
01175 end += 4
01176 (length,) = _struct_I.unpack(str[start:end])
01177 start = end
01178 end += length
01179 self.region.disparity_image.header.frame_id = str[start:end]
01180 _x = self
01181 start = end
01182 end += 8
01183 (_x.region.disparity_image.height, _x.region.disparity_image.width,) = _struct_2I.unpack(str[start:end])
01184 start = end
01185 end += 4
01186 (length,) = _struct_I.unpack(str[start:end])
01187 start = end
01188 end += length
01189 self.region.disparity_image.encoding = str[start:end]
01190 _x = self
01191 start = end
01192 end += 5
01193 (_x.region.disparity_image.is_bigendian, _x.region.disparity_image.step,) = _struct_BI.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 self.region.disparity_image.data = str[start:end]
01200 _x = self
01201 start = end
01202 end += 12
01203 (_x.region.cam_info.header.seq, _x.region.cam_info.header.stamp.secs, _x.region.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01204 start = end
01205 end += 4
01206 (length,) = _struct_I.unpack(str[start:end])
01207 start = end
01208 end += length
01209 self.region.cam_info.header.frame_id = str[start:end]
01210 _x = self
01211 start = end
01212 end += 8
01213 (_x.region.cam_info.height, _x.region.cam_info.width,) = _struct_2I.unpack(str[start:end])
01214 start = end
01215 end += 4
01216 (length,) = _struct_I.unpack(str[start:end])
01217 start = end
01218 end += length
01219 self.region.cam_info.distortion_model = str[start:end]
01220 start = end
01221 end += 4
01222 (length,) = _struct_I.unpack(str[start:end])
01223 pattern = '<%sd'%length
01224 start = end
01225 end += struct.calcsize(pattern)
01226 self.region.cam_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01227 start = end
01228 end += 72
01229 self.region.cam_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01230 start = end
01231 end += 72
01232 self.region.cam_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01233 start = end
01234 end += 96
01235 self.region.cam_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01236 _x = self
01237 start = end
01238 end += 25
01239 (_x.region.cam_info.binning_x, _x.region.cam_info.binning_y, _x.region.cam_info.roi.x_offset, _x.region.cam_info.roi.y_offset, _x.region.cam_info.roi.height, _x.region.cam_info.roi.width, _x.region.cam_info.roi.do_rectify,) = _struct_6IB.unpack(str[start:end])
01240 self.region.cam_info.roi.do_rectify = bool(self.region.cam_info.roi.do_rectify)
01241 return self
01242 except struct.error, e:
01243 raise roslib.message.DeserializationError(e) #most likely buffer underfill
01244
01245 _struct_I = roslib.message.struct_I
01246 _struct_6IB = struct.Struct("<6IB")
01247 _struct_IBI = struct.Struct("<IBI")
01248 _struct_B = struct.Struct("<B")
01249 _struct_12d = struct.Struct("<12d")
01250 _struct_f = struct.Struct("<f")
01251 _struct_i = struct.Struct("<i")
01252 _struct_BI = struct.Struct("<BI")
01253 _struct_3f = struct.Struct("<3f")
01254 _struct_3I = struct.Struct("<3I")
01255 _struct_9d = struct.Struct("<9d")
01256 _struct_B2I = struct.Struct("<B2I")
01257 _struct_4d = struct.Struct("<4d")
01258 _struct_2I = struct.Struct("<2I")
01259 _struct_3d = struct.Struct("<3d")