00001 """autogenerated by genpy from iri_perception_msgs/object_pose_detectionAction.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 actionlib_msgs.msg
00008 import geometry_msgs.msg
00009 import sensor_msgs.msg
00010 import std_msgs.msg
00011 import genpy
00012 import iri_perception_msgs.msg
00013
00014 class object_pose_detectionAction(genpy.Message):
00015 _md5sum = "df72977440854c7b9be7539c9fcc04f0"
00016 _type = "iri_perception_msgs/object_pose_detectionAction"
00017 _has_header = False
00018 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019
00020 object_pose_detectionActionGoal action_goal
00021 object_pose_detectionActionResult action_result
00022 object_pose_detectionActionFeedback action_feedback
00023
00024 ================================================================================
00025 MSG: iri_perception_msgs/object_pose_detectionActionGoal
00026 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00027
00028 Header header
00029 actionlib_msgs/GoalID goal_id
00030 object_pose_detectionGoal goal
00031
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data
00036 # in a particular coordinate frame.
00037 #
00038 # sequence ID: consecutively increasing ID
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049
00050 ================================================================================
00051 MSG: actionlib_msgs/GoalID
00052 # The stamp should store the time at which this goal was requested.
00053 # It is used by an action server when it tries to preempt all
00054 # goals that were requested before a certain time
00055 time stamp
00056
00057 # The id provides a way to associate feedback and
00058 # result message with specific goal requests. The id
00059 # specified must be unique.
00060 string id
00061
00062
00063 ================================================================================
00064 MSG: iri_perception_msgs/object_pose_detectionGoal
00065 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00066 #goal definition
00067 sensor_msgs/Image image
00068 sensor_msgs/PointCloud2 pcl
00069
00070 ================================================================================
00071 MSG: sensor_msgs/Image
00072 # This message contains an uncompressed image
00073 # (0, 0) is at top-left corner of image
00074 #
00075
00076 Header header # Header timestamp should be acquisition time of image
00077 # Header frame_id should be optical frame of camera
00078 # origin of frame should be optical center of cameara
00079 # +x should point to the right in the image
00080 # +y should point down in the image
00081 # +z should point into to plane of the image
00082 # If the frame_id here and the frame_id of the CameraInfo
00083 # message associated with the image conflict
00084 # the behavior is undefined
00085
00086 uint32 height # image height, that is, number of rows
00087 uint32 width # image width, that is, number of columns
00088
00089 # The legal values for encoding are in file src/image_encodings.cpp
00090 # If you want to standardize a new string format, join
00091 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00092
00093 string encoding # Encoding of pixels -- channel meaning, ordering, size
00094 # taken from the list of strings in src/image_encodings.cpp
00095
00096 uint8 is_bigendian # is this data bigendian?
00097 uint32 step # Full row length in bytes
00098 uint8[] data # actual matrix data, size is (step * rows)
00099
00100 ================================================================================
00101 MSG: sensor_msgs/PointCloud2
00102 # This message holds a collection of N-dimensional points, which may
00103 # contain additional information such as normals, intensity, etc. The
00104 # point data is stored as a binary blob, its layout described by the
00105 # contents of the "fields" array.
00106
00107 # The point cloud data may be organized 2d (image-like) or 1d
00108 # (unordered). Point clouds organized as 2d images may be produced by
00109 # camera depth sensors such as stereo or time-of-flight.
00110
00111 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00112 # points).
00113 Header header
00114
00115 # 2D structure of the point cloud. If the cloud is unordered, height is
00116 # 1 and width is the length of the point cloud.
00117 uint32 height
00118 uint32 width
00119
00120 # Describes the channels and their layout in the binary data blob.
00121 PointField[] fields
00122
00123 bool is_bigendian # Is this data bigendian?
00124 uint32 point_step # Length of a point in bytes
00125 uint32 row_step # Length of a row in bytes
00126 uint8[] data # Actual point data, size is (row_step*height)
00127
00128 bool is_dense # True if there are no invalid points
00129
00130 ================================================================================
00131 MSG: sensor_msgs/PointField
00132 # This message holds the description of one point entry in the
00133 # PointCloud2 message format.
00134 uint8 INT8 = 1
00135 uint8 UINT8 = 2
00136 uint8 INT16 = 3
00137 uint8 UINT16 = 4
00138 uint8 INT32 = 5
00139 uint8 UINT32 = 6
00140 uint8 FLOAT32 = 7
00141 uint8 FLOAT64 = 8
00142
00143 string name # Name of field
00144 uint32 offset # Offset from start of point struct
00145 uint8 datatype # Datatype enumeration, see above
00146 uint32 count # How many elements in the field
00147
00148 ================================================================================
00149 MSG: iri_perception_msgs/object_pose_detectionActionResult
00150 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00151
00152 Header header
00153 actionlib_msgs/GoalStatus status
00154 object_pose_detectionResult result
00155
00156 ================================================================================
00157 MSG: actionlib_msgs/GoalStatus
00158 GoalID goal_id
00159 uint8 status
00160 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00161 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00162 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00163 # and has since completed its execution (Terminal State)
00164 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00165 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00166 # to some failure (Terminal State)
00167 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00168 # because the goal was unattainable or invalid (Terminal State)
00169 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00170 # and has not yet completed execution
00171 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00172 # but the action server has not yet confirmed that the goal is canceled
00173 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00174 # and was successfully cancelled (Terminal State)
00175 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00176 # sent over the wire by an action server
00177
00178 #Allow for the user to associate a string with GoalStatus for debugging
00179 string text
00180
00181
00182 ================================================================================
00183 MSG: iri_perception_msgs/object_pose_detectionResult
00184 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00185 #result definition
00186 geometry_msgs/PoseStamped pose
00187
00188 ================================================================================
00189 MSG: geometry_msgs/PoseStamped
00190 # A Pose with reference coordinate frame and timestamp
00191 Header header
00192 Pose pose
00193
00194 ================================================================================
00195 MSG: geometry_msgs/Pose
00196 # A representation of pose in free space, composed of postion and orientation.
00197 Point position
00198 Quaternion orientation
00199
00200 ================================================================================
00201 MSG: geometry_msgs/Point
00202 # This contains the position of a point in free space
00203 float64 x
00204 float64 y
00205 float64 z
00206
00207 ================================================================================
00208 MSG: geometry_msgs/Quaternion
00209 # This represents an orientation in free space in quaternion form.
00210
00211 float64 x
00212 float64 y
00213 float64 z
00214 float64 w
00215
00216 ================================================================================
00217 MSG: iri_perception_msgs/object_pose_detectionActionFeedback
00218 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00219
00220 Header header
00221 actionlib_msgs/GoalStatus status
00222 object_pose_detectionFeedback feedback
00223
00224 ================================================================================
00225 MSG: iri_perception_msgs/object_pose_detectionFeedback
00226 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00227 #feedback
00228
00229
00230
00231 """
00232 __slots__ = ['action_goal','action_result','action_feedback']
00233 _slot_types = ['iri_perception_msgs/object_pose_detectionActionGoal','iri_perception_msgs/object_pose_detectionActionResult','iri_perception_msgs/object_pose_detectionActionFeedback']
00234
00235 def __init__(self, *args, **kwds):
00236 """
00237 Constructor. Any message fields that are implicitly/explicitly
00238 set to None will be assigned a default value. The recommend
00239 use is keyword arguments as this is more robust to future message
00240 changes. You cannot mix in-order arguments and keyword arguments.
00241
00242 The available fields are:
00243 action_goal,action_result,action_feedback
00244
00245 :param args: complete set of field values, in .msg order
00246 :param kwds: use keyword arguments corresponding to message field names
00247 to set specific fields.
00248 """
00249 if args or kwds:
00250 super(object_pose_detectionAction, self).__init__(*args, **kwds)
00251
00252 if self.action_goal is None:
00253 self.action_goal = iri_perception_msgs.msg.object_pose_detectionActionGoal()
00254 if self.action_result is None:
00255 self.action_result = iri_perception_msgs.msg.object_pose_detectionActionResult()
00256 if self.action_feedback is None:
00257 self.action_feedback = iri_perception_msgs.msg.object_pose_detectionActionFeedback()
00258 else:
00259 self.action_goal = iri_perception_msgs.msg.object_pose_detectionActionGoal()
00260 self.action_result = iri_perception_msgs.msg.object_pose_detectionActionResult()
00261 self.action_feedback = iri_perception_msgs.msg.object_pose_detectionActionFeedback()
00262
00263 def _get_types(self):
00264 """
00265 internal API method
00266 """
00267 return self._slot_types
00268
00269 def serialize(self, buff):
00270 """
00271 serialize message into buffer
00272 :param buff: buffer, ``StringIO``
00273 """
00274 try:
00275 _x = self
00276 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00277 _x = self.action_goal.header.frame_id
00278 length = len(_x)
00279 if python3 or type(_x) == unicode:
00280 _x = _x.encode('utf-8')
00281 length = len(_x)
00282 buff.write(struct.pack('<I%ss'%length, length, _x))
00283 _x = self
00284 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00285 _x = self.action_goal.goal_id.id
00286 length = len(_x)
00287 if python3 or type(_x) == unicode:
00288 _x = _x.encode('utf-8')
00289 length = len(_x)
00290 buff.write(struct.pack('<I%ss'%length, length, _x))
00291 _x = self
00292 buff.write(_struct_3I.pack(_x.action_goal.goal.image.header.seq, _x.action_goal.goal.image.header.stamp.secs, _x.action_goal.goal.image.header.stamp.nsecs))
00293 _x = self.action_goal.goal.image.header.frame_id
00294 length = len(_x)
00295 if python3 or type(_x) == unicode:
00296 _x = _x.encode('utf-8')
00297 length = len(_x)
00298 buff.write(struct.pack('<I%ss'%length, length, _x))
00299 _x = self
00300 buff.write(_struct_2I.pack(_x.action_goal.goal.image.height, _x.action_goal.goal.image.width))
00301 _x = self.action_goal.goal.image.encoding
00302 length = len(_x)
00303 if python3 or type(_x) == unicode:
00304 _x = _x.encode('utf-8')
00305 length = len(_x)
00306 buff.write(struct.pack('<I%ss'%length, length, _x))
00307 _x = self
00308 buff.write(_struct_BI.pack(_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step))
00309 _x = self.action_goal.goal.image.data
00310 length = len(_x)
00311
00312 if type(_x) in [list, tuple]:
00313 buff.write(struct.pack('<I%sB'%length, length, *_x))
00314 else:
00315 buff.write(struct.pack('<I%ss'%length, length, _x))
00316 _x = self
00317 buff.write(_struct_3I.pack(_x.action_goal.goal.pcl.header.seq, _x.action_goal.goal.pcl.header.stamp.secs, _x.action_goal.goal.pcl.header.stamp.nsecs))
00318 _x = self.action_goal.goal.pcl.header.frame_id
00319 length = len(_x)
00320 if python3 or type(_x) == unicode:
00321 _x = _x.encode('utf-8')
00322 length = len(_x)
00323 buff.write(struct.pack('<I%ss'%length, length, _x))
00324 _x = self
00325 buff.write(_struct_2I.pack(_x.action_goal.goal.pcl.height, _x.action_goal.goal.pcl.width))
00326 length = len(self.action_goal.goal.pcl.fields)
00327 buff.write(_struct_I.pack(length))
00328 for val1 in self.action_goal.goal.pcl.fields:
00329 _x = val1.name
00330 length = len(_x)
00331 if python3 or type(_x) == unicode:
00332 _x = _x.encode('utf-8')
00333 length = len(_x)
00334 buff.write(struct.pack('<I%ss'%length, length, _x))
00335 _x = val1
00336 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00337 _x = self
00338 buff.write(_struct_B2I.pack(_x.action_goal.goal.pcl.is_bigendian, _x.action_goal.goal.pcl.point_step, _x.action_goal.goal.pcl.row_step))
00339 _x = self.action_goal.goal.pcl.data
00340 length = len(_x)
00341
00342 if type(_x) in [list, tuple]:
00343 buff.write(struct.pack('<I%sB'%length, length, *_x))
00344 else:
00345 buff.write(struct.pack('<I%ss'%length, length, _x))
00346 _x = self
00347 buff.write(_struct_B3I.pack(_x.action_goal.goal.pcl.is_dense, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00348 _x = self.action_result.header.frame_id
00349 length = len(_x)
00350 if python3 or type(_x) == unicode:
00351 _x = _x.encode('utf-8')
00352 length = len(_x)
00353 buff.write(struct.pack('<I%ss'%length, length, _x))
00354 _x = self
00355 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00356 _x = self.action_result.status.goal_id.id
00357 length = len(_x)
00358 if python3 or type(_x) == unicode:
00359 _x = _x.encode('utf-8')
00360 length = len(_x)
00361 buff.write(struct.pack('<I%ss'%length, length, _x))
00362 buff.write(_struct_B.pack(self.action_result.status.status))
00363 _x = self.action_result.status.text
00364 length = len(_x)
00365 if python3 or type(_x) == unicode:
00366 _x = _x.encode('utf-8')
00367 length = len(_x)
00368 buff.write(struct.pack('<I%ss'%length, length, _x))
00369 _x = self
00370 buff.write(_struct_3I.pack(_x.action_result.result.pose.header.seq, _x.action_result.result.pose.header.stamp.secs, _x.action_result.result.pose.header.stamp.nsecs))
00371 _x = self.action_result.result.pose.header.frame_id
00372 length = len(_x)
00373 if python3 or type(_x) == unicode:
00374 _x = _x.encode('utf-8')
00375 length = len(_x)
00376 buff.write(struct.pack('<I%ss'%length, length, _x))
00377 _x = self
00378 buff.write(_struct_7d3I.pack(_x.action_result.result.pose.pose.position.x, _x.action_result.result.pose.pose.position.y, _x.action_result.result.pose.pose.position.z, _x.action_result.result.pose.pose.orientation.x, _x.action_result.result.pose.pose.orientation.y, _x.action_result.result.pose.pose.orientation.z, _x.action_result.result.pose.pose.orientation.w, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00379 _x = self.action_feedback.header.frame_id
00380 length = len(_x)
00381 if python3 or type(_x) == unicode:
00382 _x = _x.encode('utf-8')
00383 length = len(_x)
00384 buff.write(struct.pack('<I%ss'%length, length, _x))
00385 _x = self
00386 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00387 _x = self.action_feedback.status.goal_id.id
00388 length = len(_x)
00389 if python3 or type(_x) == unicode:
00390 _x = _x.encode('utf-8')
00391 length = len(_x)
00392 buff.write(struct.pack('<I%ss'%length, length, _x))
00393 buff.write(_struct_B.pack(self.action_feedback.status.status))
00394 _x = self.action_feedback.status.text
00395 length = len(_x)
00396 if python3 or type(_x) == unicode:
00397 _x = _x.encode('utf-8')
00398 length = len(_x)
00399 buff.write(struct.pack('<I%ss'%length, length, _x))
00400 except struct.error as se: self._check_types(se)
00401 except TypeError as te: self._check_types(te)
00402
00403 def deserialize(self, str):
00404 """
00405 unpack serialized message in str into this message instance
00406 :param str: byte array of serialized message, ``str``
00407 """
00408 try:
00409 if self.action_goal is None:
00410 self.action_goal = iri_perception_msgs.msg.object_pose_detectionActionGoal()
00411 if self.action_result is None:
00412 self.action_result = iri_perception_msgs.msg.object_pose_detectionActionResult()
00413 if self.action_feedback is None:
00414 self.action_feedback = iri_perception_msgs.msg.object_pose_detectionActionFeedback()
00415 end = 0
00416 _x = self
00417 start = end
00418 end += 12
00419 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00420 start = end
00421 end += 4
00422 (length,) = _struct_I.unpack(str[start:end])
00423 start = end
00424 end += length
00425 if python3:
00426 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00427 else:
00428 self.action_goal.header.frame_id = str[start:end]
00429 _x = self
00430 start = end
00431 end += 8
00432 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00433 start = end
00434 end += 4
00435 (length,) = _struct_I.unpack(str[start:end])
00436 start = end
00437 end += length
00438 if python3:
00439 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00440 else:
00441 self.action_goal.goal_id.id = str[start:end]
00442 _x = self
00443 start = end
00444 end += 12
00445 (_x.action_goal.goal.image.header.seq, _x.action_goal.goal.image.header.stamp.secs, _x.action_goal.goal.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 start = end
00450 end += length
00451 if python3:
00452 self.action_goal.goal.image.header.frame_id = str[start:end].decode('utf-8')
00453 else:
00454 self.action_goal.goal.image.header.frame_id = str[start:end]
00455 _x = self
00456 start = end
00457 end += 8
00458 (_x.action_goal.goal.image.height, _x.action_goal.goal.image.width,) = _struct_2I.unpack(str[start:end])
00459 start = end
00460 end += 4
00461 (length,) = _struct_I.unpack(str[start:end])
00462 start = end
00463 end += length
00464 if python3:
00465 self.action_goal.goal.image.encoding = str[start:end].decode('utf-8')
00466 else:
00467 self.action_goal.goal.image.encoding = str[start:end]
00468 _x = self
00469 start = end
00470 end += 5
00471 (_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step,) = _struct_BI.unpack(str[start:end])
00472 start = end
00473 end += 4
00474 (length,) = _struct_I.unpack(str[start:end])
00475 start = end
00476 end += length
00477 if python3:
00478 self.action_goal.goal.image.data = str[start:end].decode('utf-8')
00479 else:
00480 self.action_goal.goal.image.data = str[start:end]
00481 _x = self
00482 start = end
00483 end += 12
00484 (_x.action_goal.goal.pcl.header.seq, _x.action_goal.goal.pcl.header.stamp.secs, _x.action_goal.goal.pcl.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00485 start = end
00486 end += 4
00487 (length,) = _struct_I.unpack(str[start:end])
00488 start = end
00489 end += length
00490 if python3:
00491 self.action_goal.goal.pcl.header.frame_id = str[start:end].decode('utf-8')
00492 else:
00493 self.action_goal.goal.pcl.header.frame_id = str[start:end]
00494 _x = self
00495 start = end
00496 end += 8
00497 (_x.action_goal.goal.pcl.height, _x.action_goal.goal.pcl.width,) = _struct_2I.unpack(str[start:end])
00498 start = end
00499 end += 4
00500 (length,) = _struct_I.unpack(str[start:end])
00501 self.action_goal.goal.pcl.fields = []
00502 for i in range(0, length):
00503 val1 = sensor_msgs.msg.PointField()
00504 start = end
00505 end += 4
00506 (length,) = _struct_I.unpack(str[start:end])
00507 start = end
00508 end += length
00509 if python3:
00510 val1.name = str[start:end].decode('utf-8')
00511 else:
00512 val1.name = str[start:end]
00513 _x = val1
00514 start = end
00515 end += 9
00516 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00517 self.action_goal.goal.pcl.fields.append(val1)
00518 _x = self
00519 start = end
00520 end += 9
00521 (_x.action_goal.goal.pcl.is_bigendian, _x.action_goal.goal.pcl.point_step, _x.action_goal.goal.pcl.row_step,) = _struct_B2I.unpack(str[start:end])
00522 self.action_goal.goal.pcl.is_bigendian = bool(self.action_goal.goal.pcl.is_bigendian)
00523 start = end
00524 end += 4
00525 (length,) = _struct_I.unpack(str[start:end])
00526 start = end
00527 end += length
00528 if python3:
00529 self.action_goal.goal.pcl.data = str[start:end].decode('utf-8')
00530 else:
00531 self.action_goal.goal.pcl.data = str[start:end]
00532 _x = self
00533 start = end
00534 end += 13
00535 (_x.action_goal.goal.pcl.is_dense, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00536 self.action_goal.goal.pcl.is_dense = bool(self.action_goal.goal.pcl.is_dense)
00537 start = end
00538 end += 4
00539 (length,) = _struct_I.unpack(str[start:end])
00540 start = end
00541 end += length
00542 if python3:
00543 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00544 else:
00545 self.action_result.header.frame_id = str[start:end]
00546 _x = self
00547 start = end
00548 end += 8
00549 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00550 start = end
00551 end += 4
00552 (length,) = _struct_I.unpack(str[start:end])
00553 start = end
00554 end += length
00555 if python3:
00556 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00557 else:
00558 self.action_result.status.goal_id.id = str[start:end]
00559 start = end
00560 end += 1
00561 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00562 start = end
00563 end += 4
00564 (length,) = _struct_I.unpack(str[start:end])
00565 start = end
00566 end += length
00567 if python3:
00568 self.action_result.status.text = str[start:end].decode('utf-8')
00569 else:
00570 self.action_result.status.text = str[start:end]
00571 _x = self
00572 start = end
00573 end += 12
00574 (_x.action_result.result.pose.header.seq, _x.action_result.result.pose.header.stamp.secs, _x.action_result.result.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00575 start = end
00576 end += 4
00577 (length,) = _struct_I.unpack(str[start:end])
00578 start = end
00579 end += length
00580 if python3:
00581 self.action_result.result.pose.header.frame_id = str[start:end].decode('utf-8')
00582 else:
00583 self.action_result.result.pose.header.frame_id = str[start:end]
00584 _x = self
00585 start = end
00586 end += 68
00587 (_x.action_result.result.pose.pose.position.x, _x.action_result.result.pose.pose.position.y, _x.action_result.result.pose.pose.position.z, _x.action_result.result.pose.pose.orientation.x, _x.action_result.result.pose.pose.orientation.y, _x.action_result.result.pose.pose.orientation.z, _x.action_result.result.pose.pose.orientation.w, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00588 start = end
00589 end += 4
00590 (length,) = _struct_I.unpack(str[start:end])
00591 start = end
00592 end += length
00593 if python3:
00594 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00595 else:
00596 self.action_feedback.header.frame_id = str[start:end]
00597 _x = self
00598 start = end
00599 end += 8
00600 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00601 start = end
00602 end += 4
00603 (length,) = _struct_I.unpack(str[start:end])
00604 start = end
00605 end += length
00606 if python3:
00607 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00608 else:
00609 self.action_feedback.status.goal_id.id = str[start:end]
00610 start = end
00611 end += 1
00612 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00613 start = end
00614 end += 4
00615 (length,) = _struct_I.unpack(str[start:end])
00616 start = end
00617 end += length
00618 if python3:
00619 self.action_feedback.status.text = str[start:end].decode('utf-8')
00620 else:
00621 self.action_feedback.status.text = str[start:end]
00622 return self
00623 except struct.error as e:
00624 raise genpy.DeserializationError(e)
00625
00626
00627 def serialize_numpy(self, buff, numpy):
00628 """
00629 serialize message with numpy array types into buffer
00630 :param buff: buffer, ``StringIO``
00631 :param numpy: numpy python module
00632 """
00633 try:
00634 _x = self
00635 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00636 _x = self.action_goal.header.frame_id
00637 length = len(_x)
00638 if python3 or type(_x) == unicode:
00639 _x = _x.encode('utf-8')
00640 length = len(_x)
00641 buff.write(struct.pack('<I%ss'%length, length, _x))
00642 _x = self
00643 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00644 _x = self.action_goal.goal_id.id
00645 length = len(_x)
00646 if python3 or type(_x) == unicode:
00647 _x = _x.encode('utf-8')
00648 length = len(_x)
00649 buff.write(struct.pack('<I%ss'%length, length, _x))
00650 _x = self
00651 buff.write(_struct_3I.pack(_x.action_goal.goal.image.header.seq, _x.action_goal.goal.image.header.stamp.secs, _x.action_goal.goal.image.header.stamp.nsecs))
00652 _x = self.action_goal.goal.image.header.frame_id
00653 length = len(_x)
00654 if python3 or type(_x) == unicode:
00655 _x = _x.encode('utf-8')
00656 length = len(_x)
00657 buff.write(struct.pack('<I%ss'%length, length, _x))
00658 _x = self
00659 buff.write(_struct_2I.pack(_x.action_goal.goal.image.height, _x.action_goal.goal.image.width))
00660 _x = self.action_goal.goal.image.encoding
00661 length = len(_x)
00662 if python3 or type(_x) == unicode:
00663 _x = _x.encode('utf-8')
00664 length = len(_x)
00665 buff.write(struct.pack('<I%ss'%length, length, _x))
00666 _x = self
00667 buff.write(_struct_BI.pack(_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step))
00668 _x = self.action_goal.goal.image.data
00669 length = len(_x)
00670
00671 if type(_x) in [list, tuple]:
00672 buff.write(struct.pack('<I%sB'%length, length, *_x))
00673 else:
00674 buff.write(struct.pack('<I%ss'%length, length, _x))
00675 _x = self
00676 buff.write(_struct_3I.pack(_x.action_goal.goal.pcl.header.seq, _x.action_goal.goal.pcl.header.stamp.secs, _x.action_goal.goal.pcl.header.stamp.nsecs))
00677 _x = self.action_goal.goal.pcl.header.frame_id
00678 length = len(_x)
00679 if python3 or type(_x) == unicode:
00680 _x = _x.encode('utf-8')
00681 length = len(_x)
00682 buff.write(struct.pack('<I%ss'%length, length, _x))
00683 _x = self
00684 buff.write(_struct_2I.pack(_x.action_goal.goal.pcl.height, _x.action_goal.goal.pcl.width))
00685 length = len(self.action_goal.goal.pcl.fields)
00686 buff.write(_struct_I.pack(length))
00687 for val1 in self.action_goal.goal.pcl.fields:
00688 _x = val1.name
00689 length = len(_x)
00690 if python3 or type(_x) == unicode:
00691 _x = _x.encode('utf-8')
00692 length = len(_x)
00693 buff.write(struct.pack('<I%ss'%length, length, _x))
00694 _x = val1
00695 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00696 _x = self
00697 buff.write(_struct_B2I.pack(_x.action_goal.goal.pcl.is_bigendian, _x.action_goal.goal.pcl.point_step, _x.action_goal.goal.pcl.row_step))
00698 _x = self.action_goal.goal.pcl.data
00699 length = len(_x)
00700
00701 if type(_x) in [list, tuple]:
00702 buff.write(struct.pack('<I%sB'%length, length, *_x))
00703 else:
00704 buff.write(struct.pack('<I%ss'%length, length, _x))
00705 _x = self
00706 buff.write(_struct_B3I.pack(_x.action_goal.goal.pcl.is_dense, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00707 _x = self.action_result.header.frame_id
00708 length = len(_x)
00709 if python3 or type(_x) == unicode:
00710 _x = _x.encode('utf-8')
00711 length = len(_x)
00712 buff.write(struct.pack('<I%ss'%length, length, _x))
00713 _x = self
00714 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00715 _x = self.action_result.status.goal_id.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 buff.write(_struct_B.pack(self.action_result.status.status))
00722 _x = self.action_result.status.text
00723 length = len(_x)
00724 if python3 or type(_x) == unicode:
00725 _x = _x.encode('utf-8')
00726 length = len(_x)
00727 buff.write(struct.pack('<I%ss'%length, length, _x))
00728 _x = self
00729 buff.write(_struct_3I.pack(_x.action_result.result.pose.header.seq, _x.action_result.result.pose.header.stamp.secs, _x.action_result.result.pose.header.stamp.nsecs))
00730 _x = self.action_result.result.pose.header.frame_id
00731 length = len(_x)
00732 if python3 or type(_x) == unicode:
00733 _x = _x.encode('utf-8')
00734 length = len(_x)
00735 buff.write(struct.pack('<I%ss'%length, length, _x))
00736 _x = self
00737 buff.write(_struct_7d3I.pack(_x.action_result.result.pose.pose.position.x, _x.action_result.result.pose.pose.position.y, _x.action_result.result.pose.pose.position.z, _x.action_result.result.pose.pose.orientation.x, _x.action_result.result.pose.pose.orientation.y, _x.action_result.result.pose.pose.orientation.z, _x.action_result.result.pose.pose.orientation.w, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00738 _x = self.action_feedback.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_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00746 _x = self.action_feedback.status.goal_id.id
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 buff.write(_struct_B.pack(self.action_feedback.status.status))
00753 _x = self.action_feedback.status.text
00754 length = len(_x)
00755 if python3 or type(_x) == unicode:
00756 _x = _x.encode('utf-8')
00757 length = len(_x)
00758 buff.write(struct.pack('<I%ss'%length, length, _x))
00759 except struct.error as se: self._check_types(se)
00760 except TypeError as te: self._check_types(te)
00761
00762 def deserialize_numpy(self, str, numpy):
00763 """
00764 unpack serialized message in str into this message instance using numpy for array types
00765 :param str: byte array of serialized message, ``str``
00766 :param numpy: numpy python module
00767 """
00768 try:
00769 if self.action_goal is None:
00770 self.action_goal = iri_perception_msgs.msg.object_pose_detectionActionGoal()
00771 if self.action_result is None:
00772 self.action_result = iri_perception_msgs.msg.object_pose_detectionActionResult()
00773 if self.action_feedback is None:
00774 self.action_feedback = iri_perception_msgs.msg.object_pose_detectionActionFeedback()
00775 end = 0
00776 _x = self
00777 start = end
00778 end += 12
00779 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00780 start = end
00781 end += 4
00782 (length,) = _struct_I.unpack(str[start:end])
00783 start = end
00784 end += length
00785 if python3:
00786 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00787 else:
00788 self.action_goal.header.frame_id = str[start:end]
00789 _x = self
00790 start = end
00791 end += 8
00792 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00793 start = end
00794 end += 4
00795 (length,) = _struct_I.unpack(str[start:end])
00796 start = end
00797 end += length
00798 if python3:
00799 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00800 else:
00801 self.action_goal.goal_id.id = str[start:end]
00802 _x = self
00803 start = end
00804 end += 12
00805 (_x.action_goal.goal.image.header.seq, _x.action_goal.goal.image.header.stamp.secs, _x.action_goal.goal.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00806 start = end
00807 end += 4
00808 (length,) = _struct_I.unpack(str[start:end])
00809 start = end
00810 end += length
00811 if python3:
00812 self.action_goal.goal.image.header.frame_id = str[start:end].decode('utf-8')
00813 else:
00814 self.action_goal.goal.image.header.frame_id = str[start:end]
00815 _x = self
00816 start = end
00817 end += 8
00818 (_x.action_goal.goal.image.height, _x.action_goal.goal.image.width,) = _struct_2I.unpack(str[start:end])
00819 start = end
00820 end += 4
00821 (length,) = _struct_I.unpack(str[start:end])
00822 start = end
00823 end += length
00824 if python3:
00825 self.action_goal.goal.image.encoding = str[start:end].decode('utf-8')
00826 else:
00827 self.action_goal.goal.image.encoding = str[start:end]
00828 _x = self
00829 start = end
00830 end += 5
00831 (_x.action_goal.goal.image.is_bigendian, _x.action_goal.goal.image.step,) = _struct_BI.unpack(str[start:end])
00832 start = end
00833 end += 4
00834 (length,) = _struct_I.unpack(str[start:end])
00835 start = end
00836 end += length
00837 if python3:
00838 self.action_goal.goal.image.data = str[start:end].decode('utf-8')
00839 else:
00840 self.action_goal.goal.image.data = str[start:end]
00841 _x = self
00842 start = end
00843 end += 12
00844 (_x.action_goal.goal.pcl.header.seq, _x.action_goal.goal.pcl.header.stamp.secs, _x.action_goal.goal.pcl.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00845 start = end
00846 end += 4
00847 (length,) = _struct_I.unpack(str[start:end])
00848 start = end
00849 end += length
00850 if python3:
00851 self.action_goal.goal.pcl.header.frame_id = str[start:end].decode('utf-8')
00852 else:
00853 self.action_goal.goal.pcl.header.frame_id = str[start:end]
00854 _x = self
00855 start = end
00856 end += 8
00857 (_x.action_goal.goal.pcl.height, _x.action_goal.goal.pcl.width,) = _struct_2I.unpack(str[start:end])
00858 start = end
00859 end += 4
00860 (length,) = _struct_I.unpack(str[start:end])
00861 self.action_goal.goal.pcl.fields = []
00862 for i in range(0, length):
00863 val1 = sensor_msgs.msg.PointField()
00864 start = end
00865 end += 4
00866 (length,) = _struct_I.unpack(str[start:end])
00867 start = end
00868 end += length
00869 if python3:
00870 val1.name = str[start:end].decode('utf-8')
00871 else:
00872 val1.name = str[start:end]
00873 _x = val1
00874 start = end
00875 end += 9
00876 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00877 self.action_goal.goal.pcl.fields.append(val1)
00878 _x = self
00879 start = end
00880 end += 9
00881 (_x.action_goal.goal.pcl.is_bigendian, _x.action_goal.goal.pcl.point_step, _x.action_goal.goal.pcl.row_step,) = _struct_B2I.unpack(str[start:end])
00882 self.action_goal.goal.pcl.is_bigendian = bool(self.action_goal.goal.pcl.is_bigendian)
00883 start = end
00884 end += 4
00885 (length,) = _struct_I.unpack(str[start:end])
00886 start = end
00887 end += length
00888 if python3:
00889 self.action_goal.goal.pcl.data = str[start:end].decode('utf-8')
00890 else:
00891 self.action_goal.goal.pcl.data = str[start:end]
00892 _x = self
00893 start = end
00894 end += 13
00895 (_x.action_goal.goal.pcl.is_dense, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00896 self.action_goal.goal.pcl.is_dense = bool(self.action_goal.goal.pcl.is_dense)
00897 start = end
00898 end += 4
00899 (length,) = _struct_I.unpack(str[start:end])
00900 start = end
00901 end += length
00902 if python3:
00903 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00904 else:
00905 self.action_result.header.frame_id = str[start:end]
00906 _x = self
00907 start = end
00908 end += 8
00909 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00910 start = end
00911 end += 4
00912 (length,) = _struct_I.unpack(str[start:end])
00913 start = end
00914 end += length
00915 if python3:
00916 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00917 else:
00918 self.action_result.status.goal_id.id = str[start:end]
00919 start = end
00920 end += 1
00921 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00922 start = end
00923 end += 4
00924 (length,) = _struct_I.unpack(str[start:end])
00925 start = end
00926 end += length
00927 if python3:
00928 self.action_result.status.text = str[start:end].decode('utf-8')
00929 else:
00930 self.action_result.status.text = str[start:end]
00931 _x = self
00932 start = end
00933 end += 12
00934 (_x.action_result.result.pose.header.seq, _x.action_result.result.pose.header.stamp.secs, _x.action_result.result.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00935 start = end
00936 end += 4
00937 (length,) = _struct_I.unpack(str[start:end])
00938 start = end
00939 end += length
00940 if python3:
00941 self.action_result.result.pose.header.frame_id = str[start:end].decode('utf-8')
00942 else:
00943 self.action_result.result.pose.header.frame_id = str[start:end]
00944 _x = self
00945 start = end
00946 end += 68
00947 (_x.action_result.result.pose.pose.position.x, _x.action_result.result.pose.pose.position.y, _x.action_result.result.pose.pose.position.z, _x.action_result.result.pose.pose.orientation.x, _x.action_result.result.pose.pose.orientation.y, _x.action_result.result.pose.pose.orientation.z, _x.action_result.result.pose.pose.orientation.w, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00948 start = end
00949 end += 4
00950 (length,) = _struct_I.unpack(str[start:end])
00951 start = end
00952 end += length
00953 if python3:
00954 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00955 else:
00956 self.action_feedback.header.frame_id = str[start:end]
00957 _x = self
00958 start = end
00959 end += 8
00960 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00961 start = end
00962 end += 4
00963 (length,) = _struct_I.unpack(str[start:end])
00964 start = end
00965 end += length
00966 if python3:
00967 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00968 else:
00969 self.action_feedback.status.goal_id.id = str[start:end]
00970 start = end
00971 end += 1
00972 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00973 start = end
00974 end += 4
00975 (length,) = _struct_I.unpack(str[start:end])
00976 start = end
00977 end += length
00978 if python3:
00979 self.action_feedback.status.text = str[start:end].decode('utf-8')
00980 else:
00981 self.action_feedback.status.text = str[start:end]
00982 return self
00983 except struct.error as e:
00984 raise genpy.DeserializationError(e)
00985
00986 _struct_I = genpy.struct_I
00987 _struct_IBI = struct.Struct("<IBI")
00988 _struct_B = struct.Struct("<B")
00989 _struct_BI = struct.Struct("<BI")
00990 _struct_7d3I = struct.Struct("<7d3I")
00991 _struct_3I = struct.Struct("<3I")
00992 _struct_B3I = struct.Struct("<B3I")
00993 _struct_B2I = struct.Struct("<B2I")
00994 _struct_2I = struct.Struct("<2I")