00001 """autogenerated by genmsg_py from ModelObjectInHandActionResult.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import pr2_create_object_model.msg
00006 import sensor_msgs.msg
00007 import roslib.rostime
00008 import actionlib_msgs.msg
00009 import std_msgs.msg
00010
00011 class ModelObjectInHandActionResult(roslib.message.Message):
00012 _md5sum = "03a779d4458fee213a1f34cf921ec83a"
00013 _type = "pr2_create_object_model/ModelObjectInHandActionResult"
00014 _has_header = True
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016
00017 Header header
00018 actionlib_msgs/GoalStatus status
00019 ModelObjectInHandResult result
00020
00021 ================================================================================
00022 MSG: std_msgs/Header
00023 # Standard metadata for higher-level stamped data types.
00024 # This is generally used to communicate timestamped data
00025 # in a particular coordinate frame.
00026 #
00027 # sequence ID: consecutively increasing ID
00028 uint32 seq
00029 #Two-integer timestamp that is expressed as:
00030 # * stamp.secs: seconds (stamp_secs) since epoch
00031 # * stamp.nsecs: nanoseconds since stamp_secs
00032 # time-handling sugar is provided by the client library
00033 time stamp
00034 #Frame this data is associated with
00035 # 0: no frame
00036 # 1: global frame
00037 string frame_id
00038
00039 ================================================================================
00040 MSG: actionlib_msgs/GoalStatus
00041 GoalID goal_id
00042 uint8 status
00043 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00044 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00045 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00046 # and has since completed its execution (Terminal State)
00047 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00048 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00049 # to some failure (Terminal State)
00050 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00051 # because the goal was unattainable or invalid (Terminal State)
00052 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00053 # and has not yet completed execution
00054 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00055 # but the action server has not yet confirmed that the goal is canceled
00056 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00057 # and was successfully cancelled (Terminal State)
00058 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00059 # sent over the wire by an action server
00060
00061 #Allow for the user to associate a string with GoalStatus for debugging
00062 string text
00063
00064
00065 ================================================================================
00066 MSG: actionlib_msgs/GoalID
00067 # The stamp should store the time at which this goal was requested.
00068 # It is used by an action server when it tries to preempt all
00069 # goals that were requested before a certain time
00070 time stamp
00071
00072 # The id provides a way to associate feedback and
00073 # result message with specific goal requests. The id
00074 # specified must be unique.
00075 string id
00076
00077
00078 ================================================================================
00079 MSG: pr2_create_object_model/ModelObjectInHandResult
00080 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00081
00082 sensor_msgs/PointCloud2 cluster
00083 string collision_name
00084
00085
00086 ================================================================================
00087 MSG: sensor_msgs/PointCloud2
00088 # This message holds a collection of N-dimensional points, which may
00089 # contain additional information such as normals, intensity, etc. The
00090 # point data is stored as a binary blob, its layout described by the
00091 # contents of the "fields" array.
00092
00093 # The point cloud data may be organized 2d (image-like) or 1d
00094 # (unordered). Point clouds organized as 2d images may be produced by
00095 # camera depth sensors such as stereo or time-of-flight.
00096
00097 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00098 # points).
00099 Header header
00100
00101 # 2D structure of the point cloud. If the cloud is unordered, height is
00102 # 1 and width is the length of the point cloud.
00103 uint32 height
00104 uint32 width
00105
00106 # Describes the channels and their layout in the binary data blob.
00107 PointField[] fields
00108
00109 bool is_bigendian # Is this data bigendian?
00110 uint32 point_step # Length of a point in bytes
00111 uint32 row_step # Length of a row in bytes
00112 uint8[] data # Actual point data, size is (row_step*height)
00113
00114 bool is_dense # True if there are no invalid points
00115
00116 ================================================================================
00117 MSG: sensor_msgs/PointField
00118 # This message holds the description of one point entry in the
00119 # PointCloud2 message format.
00120 uint8 INT8 = 1
00121 uint8 UINT8 = 2
00122 uint8 INT16 = 3
00123 uint8 UINT16 = 4
00124 uint8 INT32 = 5
00125 uint8 UINT32 = 6
00126 uint8 FLOAT32 = 7
00127 uint8 FLOAT64 = 8
00128
00129 string name # Name of field
00130 uint32 offset # Offset from start of point struct
00131 uint8 datatype # Datatype enumeration, see above
00132 uint32 count # How many elements in the field
00133
00134 """
00135 __slots__ = ['header','status','result']
00136 _slot_types = ['Header','actionlib_msgs/GoalStatus','pr2_create_object_model/ModelObjectInHandResult']
00137
00138 def __init__(self, *args, **kwds):
00139 """
00140 Constructor. Any message fields that are implicitly/explicitly
00141 set to None will be assigned a default value. The recommend
00142 use is keyword arguments as this is more robust to future message
00143 changes. You cannot mix in-order arguments and keyword arguments.
00144
00145 The available fields are:
00146 header,status,result
00147
00148 @param args: complete set of field values, in .msg order
00149 @param kwds: use keyword arguments corresponding to message field names
00150 to set specific fields.
00151 """
00152 if args or kwds:
00153 super(ModelObjectInHandActionResult, self).__init__(*args, **kwds)
00154
00155 if self.header is None:
00156 self.header = std_msgs.msg._Header.Header()
00157 if self.status is None:
00158 self.status = actionlib_msgs.msg.GoalStatus()
00159 if self.result is None:
00160 self.result = pr2_create_object_model.msg.ModelObjectInHandResult()
00161 else:
00162 self.header = std_msgs.msg._Header.Header()
00163 self.status = actionlib_msgs.msg.GoalStatus()
00164 self.result = pr2_create_object_model.msg.ModelObjectInHandResult()
00165
00166 def _get_types(self):
00167 """
00168 internal API method
00169 """
00170 return self._slot_types
00171
00172 def serialize(self, buff):
00173 """
00174 serialize message into buffer
00175 @param buff: buffer
00176 @type buff: StringIO
00177 """
00178 try:
00179 _x = self
00180 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00181 _x = self.header.frame_id
00182 length = len(_x)
00183 buff.write(struct.pack('<I%ss'%length, length, _x))
00184 _x = self
00185 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00186 _x = self.status.goal_id.id
00187 length = len(_x)
00188 buff.write(struct.pack('<I%ss'%length, length, _x))
00189 buff.write(_struct_B.pack(self.status.status))
00190 _x = self.status.text
00191 length = len(_x)
00192 buff.write(struct.pack('<I%ss'%length, length, _x))
00193 _x = self
00194 buff.write(_struct_3I.pack(_x.result.cluster.header.seq, _x.result.cluster.header.stamp.secs, _x.result.cluster.header.stamp.nsecs))
00195 _x = self.result.cluster.header.frame_id
00196 length = len(_x)
00197 buff.write(struct.pack('<I%ss'%length, length, _x))
00198 _x = self
00199 buff.write(_struct_2I.pack(_x.result.cluster.height, _x.result.cluster.width))
00200 length = len(self.result.cluster.fields)
00201 buff.write(_struct_I.pack(length))
00202 for val1 in self.result.cluster.fields:
00203 _x = val1.name
00204 length = len(_x)
00205 buff.write(struct.pack('<I%ss'%length, length, _x))
00206 _x = val1
00207 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00208 _x = self
00209 buff.write(_struct_B2I.pack(_x.result.cluster.is_bigendian, _x.result.cluster.point_step, _x.result.cluster.row_step))
00210 _x = self.result.cluster.data
00211 length = len(_x)
00212
00213 if type(_x) in [list, tuple]:
00214 buff.write(struct.pack('<I%sB'%length, length, *_x))
00215 else:
00216 buff.write(struct.pack('<I%ss'%length, length, _x))
00217 buff.write(_struct_B.pack(self.result.cluster.is_dense))
00218 _x = self.result.collision_name
00219 length = len(_x)
00220 buff.write(struct.pack('<I%ss'%length, length, _x))
00221 except struct.error, se: self._check_types(se)
00222 except TypeError, te: self._check_types(te)
00223
00224 def deserialize(self, str):
00225 """
00226 unpack serialized message in str into this message instance
00227 @param str: byte array of serialized message
00228 @type str: str
00229 """
00230 try:
00231 if self.header is None:
00232 self.header = std_msgs.msg._Header.Header()
00233 if self.status is None:
00234 self.status = actionlib_msgs.msg.GoalStatus()
00235 if self.result is None:
00236 self.result = pr2_create_object_model.msg.ModelObjectInHandResult()
00237 end = 0
00238 _x = self
00239 start = end
00240 end += 12
00241 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00242 start = end
00243 end += 4
00244 (length,) = _struct_I.unpack(str[start:end])
00245 start = end
00246 end += length
00247 self.header.frame_id = str[start:end]
00248 _x = self
00249 start = end
00250 end += 8
00251 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00252 start = end
00253 end += 4
00254 (length,) = _struct_I.unpack(str[start:end])
00255 start = end
00256 end += length
00257 self.status.goal_id.id = str[start:end]
00258 start = end
00259 end += 1
00260 (self.status.status,) = _struct_B.unpack(str[start:end])
00261 start = end
00262 end += 4
00263 (length,) = _struct_I.unpack(str[start:end])
00264 start = end
00265 end += length
00266 self.status.text = str[start:end]
00267 _x = self
00268 start = end
00269 end += 12
00270 (_x.result.cluster.header.seq, _x.result.cluster.header.stamp.secs, _x.result.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00271 start = end
00272 end += 4
00273 (length,) = _struct_I.unpack(str[start:end])
00274 start = end
00275 end += length
00276 self.result.cluster.header.frame_id = str[start:end]
00277 _x = self
00278 start = end
00279 end += 8
00280 (_x.result.cluster.height, _x.result.cluster.width,) = _struct_2I.unpack(str[start:end])
00281 start = end
00282 end += 4
00283 (length,) = _struct_I.unpack(str[start:end])
00284 self.result.cluster.fields = []
00285 for i in xrange(0, length):
00286 val1 = sensor_msgs.msg.PointField()
00287 start = end
00288 end += 4
00289 (length,) = _struct_I.unpack(str[start:end])
00290 start = end
00291 end += length
00292 val1.name = str[start:end]
00293 _x = val1
00294 start = end
00295 end += 9
00296 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00297 self.result.cluster.fields.append(val1)
00298 _x = self
00299 start = end
00300 end += 9
00301 (_x.result.cluster.is_bigendian, _x.result.cluster.point_step, _x.result.cluster.row_step,) = _struct_B2I.unpack(str[start:end])
00302 self.result.cluster.is_bigendian = bool(self.result.cluster.is_bigendian)
00303 start = end
00304 end += 4
00305 (length,) = _struct_I.unpack(str[start:end])
00306 start = end
00307 end += length
00308 self.result.cluster.data = str[start:end]
00309 start = end
00310 end += 1
00311 (self.result.cluster.is_dense,) = _struct_B.unpack(str[start:end])
00312 self.result.cluster.is_dense = bool(self.result.cluster.is_dense)
00313 start = end
00314 end += 4
00315 (length,) = _struct_I.unpack(str[start:end])
00316 start = end
00317 end += length
00318 self.result.collision_name = str[start:end]
00319 return self
00320 except struct.error, e:
00321 raise roslib.message.DeserializationError(e)
00322
00323
00324 def serialize_numpy(self, buff, numpy):
00325 """
00326 serialize message with numpy array types into buffer
00327 @param buff: buffer
00328 @type buff: StringIO
00329 @param numpy: numpy python module
00330 @type numpy module
00331 """
00332 try:
00333 _x = self
00334 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00335 _x = self.header.frame_id
00336 length = len(_x)
00337 buff.write(struct.pack('<I%ss'%length, length, _x))
00338 _x = self
00339 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00340 _x = self.status.goal_id.id
00341 length = len(_x)
00342 buff.write(struct.pack('<I%ss'%length, length, _x))
00343 buff.write(_struct_B.pack(self.status.status))
00344 _x = self.status.text
00345 length = len(_x)
00346 buff.write(struct.pack('<I%ss'%length, length, _x))
00347 _x = self
00348 buff.write(_struct_3I.pack(_x.result.cluster.header.seq, _x.result.cluster.header.stamp.secs, _x.result.cluster.header.stamp.nsecs))
00349 _x = self.result.cluster.header.frame_id
00350 length = len(_x)
00351 buff.write(struct.pack('<I%ss'%length, length, _x))
00352 _x = self
00353 buff.write(_struct_2I.pack(_x.result.cluster.height, _x.result.cluster.width))
00354 length = len(self.result.cluster.fields)
00355 buff.write(_struct_I.pack(length))
00356 for val1 in self.result.cluster.fields:
00357 _x = val1.name
00358 length = len(_x)
00359 buff.write(struct.pack('<I%ss'%length, length, _x))
00360 _x = val1
00361 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00362 _x = self
00363 buff.write(_struct_B2I.pack(_x.result.cluster.is_bigendian, _x.result.cluster.point_step, _x.result.cluster.row_step))
00364 _x = self.result.cluster.data
00365 length = len(_x)
00366
00367 if type(_x) in [list, tuple]:
00368 buff.write(struct.pack('<I%sB'%length, length, *_x))
00369 else:
00370 buff.write(struct.pack('<I%ss'%length, length, _x))
00371 buff.write(_struct_B.pack(self.result.cluster.is_dense))
00372 _x = self.result.collision_name
00373 length = len(_x)
00374 buff.write(struct.pack('<I%ss'%length, length, _x))
00375 except struct.error, se: self._check_types(se)
00376 except TypeError, te: self._check_types(te)
00377
00378 def deserialize_numpy(self, str, numpy):
00379 """
00380 unpack serialized message in str into this message instance using numpy for array types
00381 @param str: byte array of serialized message
00382 @type str: str
00383 @param numpy: numpy python module
00384 @type numpy: module
00385 """
00386 try:
00387 if self.header is None:
00388 self.header = std_msgs.msg._Header.Header()
00389 if self.status is None:
00390 self.status = actionlib_msgs.msg.GoalStatus()
00391 if self.result is None:
00392 self.result = pr2_create_object_model.msg.ModelObjectInHandResult()
00393 end = 0
00394 _x = self
00395 start = end
00396 end += 12
00397 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00398 start = end
00399 end += 4
00400 (length,) = _struct_I.unpack(str[start:end])
00401 start = end
00402 end += length
00403 self.header.frame_id = str[start:end]
00404 _x = self
00405 start = end
00406 end += 8
00407 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00408 start = end
00409 end += 4
00410 (length,) = _struct_I.unpack(str[start:end])
00411 start = end
00412 end += length
00413 self.status.goal_id.id = str[start:end]
00414 start = end
00415 end += 1
00416 (self.status.status,) = _struct_B.unpack(str[start:end])
00417 start = end
00418 end += 4
00419 (length,) = _struct_I.unpack(str[start:end])
00420 start = end
00421 end += length
00422 self.status.text = str[start:end]
00423 _x = self
00424 start = end
00425 end += 12
00426 (_x.result.cluster.header.seq, _x.result.cluster.header.stamp.secs, _x.result.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00427 start = end
00428 end += 4
00429 (length,) = _struct_I.unpack(str[start:end])
00430 start = end
00431 end += length
00432 self.result.cluster.header.frame_id = str[start:end]
00433 _x = self
00434 start = end
00435 end += 8
00436 (_x.result.cluster.height, _x.result.cluster.width,) = _struct_2I.unpack(str[start:end])
00437 start = end
00438 end += 4
00439 (length,) = _struct_I.unpack(str[start:end])
00440 self.result.cluster.fields = []
00441 for i in xrange(0, length):
00442 val1 = sensor_msgs.msg.PointField()
00443 start = end
00444 end += 4
00445 (length,) = _struct_I.unpack(str[start:end])
00446 start = end
00447 end += length
00448 val1.name = str[start:end]
00449 _x = val1
00450 start = end
00451 end += 9
00452 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00453 self.result.cluster.fields.append(val1)
00454 _x = self
00455 start = end
00456 end += 9
00457 (_x.result.cluster.is_bigendian, _x.result.cluster.point_step, _x.result.cluster.row_step,) = _struct_B2I.unpack(str[start:end])
00458 self.result.cluster.is_bigendian = bool(self.result.cluster.is_bigendian)
00459 start = end
00460 end += 4
00461 (length,) = _struct_I.unpack(str[start:end])
00462 start = end
00463 end += length
00464 self.result.cluster.data = str[start:end]
00465 start = end
00466 end += 1
00467 (self.result.cluster.is_dense,) = _struct_B.unpack(str[start:end])
00468 self.result.cluster.is_dense = bool(self.result.cluster.is_dense)
00469 start = end
00470 end += 4
00471 (length,) = _struct_I.unpack(str[start:end])
00472 start = end
00473 end += length
00474 self.result.collision_name = str[start:end]
00475 return self
00476 except struct.error, e:
00477 raise roslib.message.DeserializationError(e)
00478
00479 _struct_I = roslib.message.struct_I
00480 _struct_IBI = struct.Struct("<IBI")
00481 _struct_3I = struct.Struct("<3I")
00482 _struct_B = struct.Struct("<B")
00483 _struct_2I = struct.Struct("<2I")
00484 _struct_B2I = struct.Struct("<B2I")