00001 """autogenerated by genmsg_py from ObjectInHand.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import std_msgs.msg
00006 import sensor_msgs.msg
00007
00008 class ObjectInHand(roslib.message.Message):
00009 _md5sum = "4fc0573025d65bdcd1b2ae03b3b53c3e"
00010 _type = "pr2_create_object_model/ObjectInHand"
00011 _has_header = False
00012 _full_text = """string arm_name
00013 sensor_msgs/PointCloud2 cluster
00014 string collision_name
00015
00016 ================================================================================
00017 MSG: sensor_msgs/PointCloud2
00018 # This message holds a collection of N-dimensional points, which may
00019 # contain additional information such as normals, intensity, etc. The
00020 # point data is stored as a binary blob, its layout described by the
00021 # contents of the "fields" array.
00022
00023 # The point cloud data may be organized 2d (image-like) or 1d
00024 # (unordered). Point clouds organized as 2d images may be produced by
00025 # camera depth sensors such as stereo or time-of-flight.
00026
00027 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00028 # points).
00029 Header header
00030
00031 # 2D structure of the point cloud. If the cloud is unordered, height is
00032 # 1 and width is the length of the point cloud.
00033 uint32 height
00034 uint32 width
00035
00036 # Describes the channels and their layout in the binary data blob.
00037 PointField[] fields
00038
00039 bool is_bigendian # Is this data bigendian?
00040 uint32 point_step # Length of a point in bytes
00041 uint32 row_step # Length of a row in bytes
00042 uint8[] data # Actual point data, size is (row_step*height)
00043
00044 bool is_dense # True if there are no invalid points
00045
00046 ================================================================================
00047 MSG: std_msgs/Header
00048 # Standard metadata for higher-level stamped data types.
00049 # This is generally used to communicate timestamped data
00050 # in a particular coordinate frame.
00051 #
00052 # sequence ID: consecutively increasing ID
00053 uint32 seq
00054 #Two-integer timestamp that is expressed as:
00055 # * stamp.secs: seconds (stamp_secs) since epoch
00056 # * stamp.nsecs: nanoseconds since stamp_secs
00057 # time-handling sugar is provided by the client library
00058 time stamp
00059 #Frame this data is associated with
00060 # 0: no frame
00061 # 1: global frame
00062 string frame_id
00063
00064 ================================================================================
00065 MSG: sensor_msgs/PointField
00066 # This message holds the description of one point entry in the
00067 # PointCloud2 message format.
00068 uint8 INT8 = 1
00069 uint8 UINT8 = 2
00070 uint8 INT16 = 3
00071 uint8 UINT16 = 4
00072 uint8 INT32 = 5
00073 uint8 UINT32 = 6
00074 uint8 FLOAT32 = 7
00075 uint8 FLOAT64 = 8
00076
00077 string name # Name of field
00078 uint32 offset # Offset from start of point struct
00079 uint8 datatype # Datatype enumeration, see above
00080 uint32 count # How many elements in the field
00081
00082 """
00083 __slots__ = ['arm_name','cluster','collision_name']
00084 _slot_types = ['string','sensor_msgs/PointCloud2','string']
00085
00086 def __init__(self, *args, **kwds):
00087 """
00088 Constructor. Any message fields that are implicitly/explicitly
00089 set to None will be assigned a default value. The recommend
00090 use is keyword arguments as this is more robust to future message
00091 changes. You cannot mix in-order arguments and keyword arguments.
00092
00093 The available fields are:
00094 arm_name,cluster,collision_name
00095
00096 @param args: complete set of field values, in .msg order
00097 @param kwds: use keyword arguments corresponding to message field names
00098 to set specific fields.
00099 """
00100 if args or kwds:
00101 super(ObjectInHand, self).__init__(*args, **kwds)
00102
00103 if self.arm_name is None:
00104 self.arm_name = ''
00105 if self.cluster is None:
00106 self.cluster = sensor_msgs.msg.PointCloud2()
00107 if self.collision_name is None:
00108 self.collision_name = ''
00109 else:
00110 self.arm_name = ''
00111 self.cluster = sensor_msgs.msg.PointCloud2()
00112 self.collision_name = ''
00113
00114 def _get_types(self):
00115 """
00116 internal API method
00117 """
00118 return self._slot_types
00119
00120 def serialize(self, buff):
00121 """
00122 serialize message into buffer
00123 @param buff: buffer
00124 @type buff: StringIO
00125 """
00126 try:
00127 _x = self.arm_name
00128 length = len(_x)
00129 buff.write(struct.pack('<I%ss'%length, length, _x))
00130 _x = self
00131 buff.write(_struct_3I.pack(_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs))
00132 _x = self.cluster.header.frame_id
00133 length = len(_x)
00134 buff.write(struct.pack('<I%ss'%length, length, _x))
00135 _x = self
00136 buff.write(_struct_2I.pack(_x.cluster.height, _x.cluster.width))
00137 length = len(self.cluster.fields)
00138 buff.write(_struct_I.pack(length))
00139 for val1 in self.cluster.fields:
00140 _x = val1.name
00141 length = len(_x)
00142 buff.write(struct.pack('<I%ss'%length, length, _x))
00143 _x = val1
00144 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00145 _x = self
00146 buff.write(_struct_B2I.pack(_x.cluster.is_bigendian, _x.cluster.point_step, _x.cluster.row_step))
00147 _x = self.cluster.data
00148 length = len(_x)
00149
00150 if type(_x) in [list, tuple]:
00151 buff.write(struct.pack('<I%sB'%length, length, *_x))
00152 else:
00153 buff.write(struct.pack('<I%ss'%length, length, _x))
00154 buff.write(_struct_B.pack(self.cluster.is_dense))
00155 _x = self.collision_name
00156 length = len(_x)
00157 buff.write(struct.pack('<I%ss'%length, length, _x))
00158 except struct.error, se: self._check_types(se)
00159 except TypeError, te: self._check_types(te)
00160
00161 def deserialize(self, str):
00162 """
00163 unpack serialized message in str into this message instance
00164 @param str: byte array of serialized message
00165 @type str: str
00166 """
00167 try:
00168 if self.cluster is None:
00169 self.cluster = sensor_msgs.msg.PointCloud2()
00170 end = 0
00171 start = end
00172 end += 4
00173 (length,) = _struct_I.unpack(str[start:end])
00174 start = end
00175 end += length
00176 self.arm_name = str[start:end]
00177 _x = self
00178 start = end
00179 end += 12
00180 (_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00181 start = end
00182 end += 4
00183 (length,) = _struct_I.unpack(str[start:end])
00184 start = end
00185 end += length
00186 self.cluster.header.frame_id = str[start:end]
00187 _x = self
00188 start = end
00189 end += 8
00190 (_x.cluster.height, _x.cluster.width,) = _struct_2I.unpack(str[start:end])
00191 start = end
00192 end += 4
00193 (length,) = _struct_I.unpack(str[start:end])
00194 self.cluster.fields = []
00195 for i in xrange(0, length):
00196 val1 = sensor_msgs.msg.PointField()
00197 start = end
00198 end += 4
00199 (length,) = _struct_I.unpack(str[start:end])
00200 start = end
00201 end += length
00202 val1.name = str[start:end]
00203 _x = val1
00204 start = end
00205 end += 9
00206 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00207 self.cluster.fields.append(val1)
00208 _x = self
00209 start = end
00210 end += 9
00211 (_x.cluster.is_bigendian, _x.cluster.point_step, _x.cluster.row_step,) = _struct_B2I.unpack(str[start:end])
00212 self.cluster.is_bigendian = bool(self.cluster.is_bigendian)
00213 start = end
00214 end += 4
00215 (length,) = _struct_I.unpack(str[start:end])
00216 start = end
00217 end += length
00218 self.cluster.data = str[start:end]
00219 start = end
00220 end += 1
00221 (self.cluster.is_dense,) = _struct_B.unpack(str[start:end])
00222 self.cluster.is_dense = bool(self.cluster.is_dense)
00223 start = end
00224 end += 4
00225 (length,) = _struct_I.unpack(str[start:end])
00226 start = end
00227 end += length
00228 self.collision_name = str[start:end]
00229 return self
00230 except struct.error, e:
00231 raise roslib.message.DeserializationError(e)
00232
00233
00234 def serialize_numpy(self, buff, numpy):
00235 """
00236 serialize message with numpy array types into buffer
00237 @param buff: buffer
00238 @type buff: StringIO
00239 @param numpy: numpy python module
00240 @type numpy module
00241 """
00242 try:
00243 _x = self.arm_name
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 _x = self
00247 buff.write(_struct_3I.pack(_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs))
00248 _x = self.cluster.header.frame_id
00249 length = len(_x)
00250 buff.write(struct.pack('<I%ss'%length, length, _x))
00251 _x = self
00252 buff.write(_struct_2I.pack(_x.cluster.height, _x.cluster.width))
00253 length = len(self.cluster.fields)
00254 buff.write(_struct_I.pack(length))
00255 for val1 in self.cluster.fields:
00256 _x = val1.name
00257 length = len(_x)
00258 buff.write(struct.pack('<I%ss'%length, length, _x))
00259 _x = val1
00260 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00261 _x = self
00262 buff.write(_struct_B2I.pack(_x.cluster.is_bigendian, _x.cluster.point_step, _x.cluster.row_step))
00263 _x = self.cluster.data
00264 length = len(_x)
00265
00266 if type(_x) in [list, tuple]:
00267 buff.write(struct.pack('<I%sB'%length, length, *_x))
00268 else:
00269 buff.write(struct.pack('<I%ss'%length, length, _x))
00270 buff.write(_struct_B.pack(self.cluster.is_dense))
00271 _x = self.collision_name
00272 length = len(_x)
00273 buff.write(struct.pack('<I%ss'%length, length, _x))
00274 except struct.error, se: self._check_types(se)
00275 except TypeError, te: self._check_types(te)
00276
00277 def deserialize_numpy(self, str, numpy):
00278 """
00279 unpack serialized message in str into this message instance using numpy for array types
00280 @param str: byte array of serialized message
00281 @type str: str
00282 @param numpy: numpy python module
00283 @type numpy: module
00284 """
00285 try:
00286 if self.cluster is None:
00287 self.cluster = sensor_msgs.msg.PointCloud2()
00288 end = 0
00289 start = end
00290 end += 4
00291 (length,) = _struct_I.unpack(str[start:end])
00292 start = end
00293 end += length
00294 self.arm_name = str[start:end]
00295 _x = self
00296 start = end
00297 end += 12
00298 (_x.cluster.header.seq, _x.cluster.header.stamp.secs, _x.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00299 start = end
00300 end += 4
00301 (length,) = _struct_I.unpack(str[start:end])
00302 start = end
00303 end += length
00304 self.cluster.header.frame_id = str[start:end]
00305 _x = self
00306 start = end
00307 end += 8
00308 (_x.cluster.height, _x.cluster.width,) = _struct_2I.unpack(str[start:end])
00309 start = end
00310 end += 4
00311 (length,) = _struct_I.unpack(str[start:end])
00312 self.cluster.fields = []
00313 for i in xrange(0, length):
00314 val1 = sensor_msgs.msg.PointField()
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 start = end
00319 end += length
00320 val1.name = str[start:end]
00321 _x = val1
00322 start = end
00323 end += 9
00324 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00325 self.cluster.fields.append(val1)
00326 _x = self
00327 start = end
00328 end += 9
00329 (_x.cluster.is_bigendian, _x.cluster.point_step, _x.cluster.row_step,) = _struct_B2I.unpack(str[start:end])
00330 self.cluster.is_bigendian = bool(self.cluster.is_bigendian)
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 self.cluster.data = str[start:end]
00337 start = end
00338 end += 1
00339 (self.cluster.is_dense,) = _struct_B.unpack(str[start:end])
00340 self.cluster.is_dense = bool(self.cluster.is_dense)
00341 start = end
00342 end += 4
00343 (length,) = _struct_I.unpack(str[start:end])
00344 start = end
00345 end += length
00346 self.collision_name = str[start:end]
00347 return self
00348 except struct.error, e:
00349 raise roslib.message.DeserializationError(e)
00350
00351 _struct_I = roslib.message.struct_I
00352 _struct_IBI = struct.Struct("<IBI")
00353 _struct_3I = struct.Struct("<3I")
00354 _struct_B = struct.Struct("<B")
00355 _struct_2I = struct.Struct("<2I")
00356 _struct_B2I = struct.Struct("<B2I")