00001 """autogenerated by genpy from object_manipulation_msgs/FindContainerAction.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 object_manipulation_msgs.msg
00008 import actionlib_msgs.msg
00009 import geometry_msgs.msg
00010 import sensor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013
00014 class FindContainerAction(genpy.Message):
00015 _md5sum = "924e0c14e65addf50f9c46889a92a8e8"
00016 _type = "object_manipulation_msgs/FindContainerAction"
00017 _has_header = False
00018 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019
00020 FindContainerActionGoal action_goal
00021 FindContainerActionResult action_result
00022 FindContainerActionFeedback action_feedback
00023
00024 ================================================================================
00025 MSG: object_manipulation_msgs/FindContainerActionGoal
00026 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00027
00028 Header header
00029 actionlib_msgs/GoalID goal_id
00030 FindContainerGoal 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: object_manipulation_msgs/FindContainerGoal
00065 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00066 # The cloud
00067 sensor_msgs/PointCloud2 cloud
00068
00069 # starting estimate of bounding box
00070 # all output will be in this frame
00071 # Assumes axis-aligned with header frame,
00072 # and WON'T take orientation into account.
00073 geometry_msgs/PoseStamped box_pose
00074 geometry_msgs/Vector3 box_dims
00075
00076 # the direction that the container opens (in bounding box header frame)
00077 geometry_msgs/Vector3 opening_dir
00078
00079
00080 ================================================================================
00081 MSG: sensor_msgs/PointCloud2
00082 # This message holds a collection of N-dimensional points, which may
00083 # contain additional information such as normals, intensity, etc. The
00084 # point data is stored as a binary blob, its layout described by the
00085 # contents of the "fields" array.
00086
00087 # The point cloud data may be organized 2d (image-like) or 1d
00088 # (unordered). Point clouds organized as 2d images may be produced by
00089 # camera depth sensors such as stereo or time-of-flight.
00090
00091 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00092 # points).
00093 Header header
00094
00095 # 2D structure of the point cloud. If the cloud is unordered, height is
00096 # 1 and width is the length of the point cloud.
00097 uint32 height
00098 uint32 width
00099
00100 # Describes the channels and their layout in the binary data blob.
00101 PointField[] fields
00102
00103 bool is_bigendian # Is this data bigendian?
00104 uint32 point_step # Length of a point in bytes
00105 uint32 row_step # Length of a row in bytes
00106 uint8[] data # Actual point data, size is (row_step*height)
00107
00108 bool is_dense # True if there are no invalid points
00109
00110 ================================================================================
00111 MSG: sensor_msgs/PointField
00112 # This message holds the description of one point entry in the
00113 # PointCloud2 message format.
00114 uint8 INT8 = 1
00115 uint8 UINT8 = 2
00116 uint8 INT16 = 3
00117 uint8 UINT16 = 4
00118 uint8 INT32 = 5
00119 uint8 UINT32 = 6
00120 uint8 FLOAT32 = 7
00121 uint8 FLOAT64 = 8
00122
00123 string name # Name of field
00124 uint32 offset # Offset from start of point struct
00125 uint8 datatype # Datatype enumeration, see above
00126 uint32 count # How many elements in the field
00127
00128 ================================================================================
00129 MSG: geometry_msgs/PoseStamped
00130 # A Pose with reference coordinate frame and timestamp
00131 Header header
00132 Pose pose
00133
00134 ================================================================================
00135 MSG: geometry_msgs/Pose
00136 # A representation of pose in free space, composed of postion and orientation.
00137 Point position
00138 Quaternion orientation
00139
00140 ================================================================================
00141 MSG: geometry_msgs/Point
00142 # This contains the position of a point in free space
00143 float64 x
00144 float64 y
00145 float64 z
00146
00147 ================================================================================
00148 MSG: geometry_msgs/Quaternion
00149 # This represents an orientation in free space in quaternion form.
00150
00151 float64 x
00152 float64 y
00153 float64 z
00154 float64 w
00155
00156 ================================================================================
00157 MSG: geometry_msgs/Vector3
00158 # This represents a vector in free space.
00159
00160 float64 x
00161 float64 y
00162 float64 z
00163 ================================================================================
00164 MSG: object_manipulation_msgs/FindContainerActionResult
00165 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00166
00167 Header header
00168 actionlib_msgs/GoalStatus status
00169 FindContainerResult result
00170
00171 ================================================================================
00172 MSG: actionlib_msgs/GoalStatus
00173 GoalID goal_id
00174 uint8 status
00175 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00176 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00177 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00178 # and has since completed its execution (Terminal State)
00179 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00180 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00181 # to some failure (Terminal State)
00182 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00183 # because the goal was unattainable or invalid (Terminal State)
00184 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00185 # and has not yet completed execution
00186 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00187 # but the action server has not yet confirmed that the goal is canceled
00188 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00189 # and was successfully cancelled (Terminal State)
00190 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00191 # sent over the wire by an action server
00192
00193 #Allow for the user to associate a string with GoalStatus for debugging
00194 string text
00195
00196
00197 ================================================================================
00198 MSG: object_manipulation_msgs/FindContainerResult
00199 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00200 # refined pose and dimensions of bounding box for container
00201 geometry_msgs/PoseStamped box_pose
00202 geometry_msgs/Vector3 box_dims
00203
00204 # cloud chunks of stuff in container, and container
00205 sensor_msgs/PointCloud2 contents
00206 sensor_msgs/PointCloud2 container
00207 sensor_msgs/PointCloud2[] clusters
00208
00209
00210 ================================================================================
00211 MSG: object_manipulation_msgs/FindContainerActionFeedback
00212 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00213
00214 Header header
00215 actionlib_msgs/GoalStatus status
00216 FindContainerFeedback feedback
00217
00218 ================================================================================
00219 MSG: object_manipulation_msgs/FindContainerFeedback
00220 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00221
00222
00223
00224 """
00225 __slots__ = ['action_goal','action_result','action_feedback']
00226 _slot_types = ['object_manipulation_msgs/FindContainerActionGoal','object_manipulation_msgs/FindContainerActionResult','object_manipulation_msgs/FindContainerActionFeedback']
00227
00228 def __init__(self, *args, **kwds):
00229 """
00230 Constructor. Any message fields that are implicitly/explicitly
00231 set to None will be assigned a default value. The recommend
00232 use is keyword arguments as this is more robust to future message
00233 changes. You cannot mix in-order arguments and keyword arguments.
00234
00235 The available fields are:
00236 action_goal,action_result,action_feedback
00237
00238 :param args: complete set of field values, in .msg order
00239 :param kwds: use keyword arguments corresponding to message field names
00240 to set specific fields.
00241 """
00242 if args or kwds:
00243 super(FindContainerAction, self).__init__(*args, **kwds)
00244
00245 if self.action_goal is None:
00246 self.action_goal = object_manipulation_msgs.msg.FindContainerActionGoal()
00247 if self.action_result is None:
00248 self.action_result = object_manipulation_msgs.msg.FindContainerActionResult()
00249 if self.action_feedback is None:
00250 self.action_feedback = object_manipulation_msgs.msg.FindContainerActionFeedback()
00251 else:
00252 self.action_goal = object_manipulation_msgs.msg.FindContainerActionGoal()
00253 self.action_result = object_manipulation_msgs.msg.FindContainerActionResult()
00254 self.action_feedback = object_manipulation_msgs.msg.FindContainerActionFeedback()
00255
00256 def _get_types(self):
00257 """
00258 internal API method
00259 """
00260 return self._slot_types
00261
00262 def serialize(self, buff):
00263 """
00264 serialize message into buffer
00265 :param buff: buffer, ``StringIO``
00266 """
00267 try:
00268 _x = self
00269 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00270 _x = self.action_goal.header.frame_id
00271 length = len(_x)
00272 if python3 or type(_x) == unicode:
00273 _x = _x.encode('utf-8')
00274 length = len(_x)
00275 buff.write(struct.pack('<I%ss'%length, length, _x))
00276 _x = self
00277 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00278 _x = self.action_goal.goal_id.id
00279 length = len(_x)
00280 if python3 or type(_x) == unicode:
00281 _x = _x.encode('utf-8')
00282 length = len(_x)
00283 buff.write(struct.pack('<I%ss'%length, length, _x))
00284 _x = self
00285 buff.write(_struct_3I.pack(_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs))
00286 _x = self.action_goal.goal.cloud.header.frame_id
00287 length = len(_x)
00288 if python3 or type(_x) == unicode:
00289 _x = _x.encode('utf-8')
00290 length = len(_x)
00291 buff.write(struct.pack('<I%ss'%length, length, _x))
00292 _x = self
00293 buff.write(_struct_2I.pack(_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width))
00294 length = len(self.action_goal.goal.cloud.fields)
00295 buff.write(_struct_I.pack(length))
00296 for val1 in self.action_goal.goal.cloud.fields:
00297 _x = val1.name
00298 length = len(_x)
00299 if python3 or type(_x) == unicode:
00300 _x = _x.encode('utf-8')
00301 length = len(_x)
00302 buff.write(struct.pack('<I%ss'%length, length, _x))
00303 _x = val1
00304 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00305 _x = self
00306 buff.write(_struct_B2I.pack(_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step))
00307 _x = self.action_goal.goal.cloud.data
00308 length = len(_x)
00309
00310 if type(_x) in [list, tuple]:
00311 buff.write(struct.pack('<I%sB'%length, length, *_x))
00312 else:
00313 buff.write(struct.pack('<I%ss'%length, length, _x))
00314 _x = self
00315 buff.write(_struct_B3I.pack(_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.box_pose.header.seq, _x.action_goal.goal.box_pose.header.stamp.secs, _x.action_goal.goal.box_pose.header.stamp.nsecs))
00316 _x = self.action_goal.goal.box_pose.header.frame_id
00317 length = len(_x)
00318 if python3 or type(_x) == unicode:
00319 _x = _x.encode('utf-8')
00320 length = len(_x)
00321 buff.write(struct.pack('<I%ss'%length, length, _x))
00322 _x = self
00323 buff.write(_struct_13d3I.pack(_x.action_goal.goal.box_pose.pose.position.x, _x.action_goal.goal.box_pose.pose.position.y, _x.action_goal.goal.box_pose.pose.position.z, _x.action_goal.goal.box_pose.pose.orientation.x, _x.action_goal.goal.box_pose.pose.orientation.y, _x.action_goal.goal.box_pose.pose.orientation.z, _x.action_goal.goal.box_pose.pose.orientation.w, _x.action_goal.goal.box_dims.x, _x.action_goal.goal.box_dims.y, _x.action_goal.goal.box_dims.z, _x.action_goal.goal.opening_dir.x, _x.action_goal.goal.opening_dir.y, _x.action_goal.goal.opening_dir.z, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00324 _x = self.action_result.header.frame_id
00325 length = len(_x)
00326 if python3 or type(_x) == unicode:
00327 _x = _x.encode('utf-8')
00328 length = len(_x)
00329 buff.write(struct.pack('<I%ss'%length, length, _x))
00330 _x = self
00331 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00332 _x = self.action_result.status.goal_id.id
00333 length = len(_x)
00334 if python3 or type(_x) == unicode:
00335 _x = _x.encode('utf-8')
00336 length = len(_x)
00337 buff.write(struct.pack('<I%ss'%length, length, _x))
00338 buff.write(_struct_B.pack(self.action_result.status.status))
00339 _x = self.action_result.status.text
00340 length = len(_x)
00341 if python3 or type(_x) == unicode:
00342 _x = _x.encode('utf-8')
00343 length = len(_x)
00344 buff.write(struct.pack('<I%ss'%length, length, _x))
00345 _x = self
00346 buff.write(_struct_3I.pack(_x.action_result.result.box_pose.header.seq, _x.action_result.result.box_pose.header.stamp.secs, _x.action_result.result.box_pose.header.stamp.nsecs))
00347 _x = self.action_result.result.box_pose.header.frame_id
00348 length = len(_x)
00349 if python3 or type(_x) == unicode:
00350 _x = _x.encode('utf-8')
00351 length = len(_x)
00352 buff.write(struct.pack('<I%ss'%length, length, _x))
00353 _x = self
00354 buff.write(_struct_10d3I.pack(_x.action_result.result.box_pose.pose.position.x, _x.action_result.result.box_pose.pose.position.y, _x.action_result.result.box_pose.pose.position.z, _x.action_result.result.box_pose.pose.orientation.x, _x.action_result.result.box_pose.pose.orientation.y, _x.action_result.result.box_pose.pose.orientation.z, _x.action_result.result.box_pose.pose.orientation.w, _x.action_result.result.box_dims.x, _x.action_result.result.box_dims.y, _x.action_result.result.box_dims.z, _x.action_result.result.contents.header.seq, _x.action_result.result.contents.header.stamp.secs, _x.action_result.result.contents.header.stamp.nsecs))
00355 _x = self.action_result.result.contents.header.frame_id
00356 length = len(_x)
00357 if python3 or type(_x) == unicode:
00358 _x = _x.encode('utf-8')
00359 length = len(_x)
00360 buff.write(struct.pack('<I%ss'%length, length, _x))
00361 _x = self
00362 buff.write(_struct_2I.pack(_x.action_result.result.contents.height, _x.action_result.result.contents.width))
00363 length = len(self.action_result.result.contents.fields)
00364 buff.write(_struct_I.pack(length))
00365 for val1 in self.action_result.result.contents.fields:
00366 _x = val1.name
00367 length = len(_x)
00368 if python3 or type(_x) == unicode:
00369 _x = _x.encode('utf-8')
00370 length = len(_x)
00371 buff.write(struct.pack('<I%ss'%length, length, _x))
00372 _x = val1
00373 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00374 _x = self
00375 buff.write(_struct_B2I.pack(_x.action_result.result.contents.is_bigendian, _x.action_result.result.contents.point_step, _x.action_result.result.contents.row_step))
00376 _x = self.action_result.result.contents.data
00377 length = len(_x)
00378
00379 if type(_x) in [list, tuple]:
00380 buff.write(struct.pack('<I%sB'%length, length, *_x))
00381 else:
00382 buff.write(struct.pack('<I%ss'%length, length, _x))
00383 _x = self
00384 buff.write(_struct_B3I.pack(_x.action_result.result.contents.is_dense, _x.action_result.result.container.header.seq, _x.action_result.result.container.header.stamp.secs, _x.action_result.result.container.header.stamp.nsecs))
00385 _x = self.action_result.result.container.header.frame_id
00386 length = len(_x)
00387 if python3 or type(_x) == unicode:
00388 _x = _x.encode('utf-8')
00389 length = len(_x)
00390 buff.write(struct.pack('<I%ss'%length, length, _x))
00391 _x = self
00392 buff.write(_struct_2I.pack(_x.action_result.result.container.height, _x.action_result.result.container.width))
00393 length = len(self.action_result.result.container.fields)
00394 buff.write(_struct_I.pack(length))
00395 for val1 in self.action_result.result.container.fields:
00396 _x = val1.name
00397 length = len(_x)
00398 if python3 or type(_x) == unicode:
00399 _x = _x.encode('utf-8')
00400 length = len(_x)
00401 buff.write(struct.pack('<I%ss'%length, length, _x))
00402 _x = val1
00403 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00404 _x = self
00405 buff.write(_struct_B2I.pack(_x.action_result.result.container.is_bigendian, _x.action_result.result.container.point_step, _x.action_result.result.container.row_step))
00406 _x = self.action_result.result.container.data
00407 length = len(_x)
00408
00409 if type(_x) in [list, tuple]:
00410 buff.write(struct.pack('<I%sB'%length, length, *_x))
00411 else:
00412 buff.write(struct.pack('<I%ss'%length, length, _x))
00413 buff.write(_struct_B.pack(self.action_result.result.container.is_dense))
00414 length = len(self.action_result.result.clusters)
00415 buff.write(_struct_I.pack(length))
00416 for val1 in self.action_result.result.clusters:
00417 _v1 = val1.header
00418 buff.write(_struct_I.pack(_v1.seq))
00419 _v2 = _v1.stamp
00420 _x = _v2
00421 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00422 _x = _v1.frame_id
00423 length = len(_x)
00424 if python3 or type(_x) == unicode:
00425 _x = _x.encode('utf-8')
00426 length = len(_x)
00427 buff.write(struct.pack('<I%ss'%length, length, _x))
00428 _x = val1
00429 buff.write(_struct_2I.pack(_x.height, _x.width))
00430 length = len(val1.fields)
00431 buff.write(_struct_I.pack(length))
00432 for val2 in val1.fields:
00433 _x = val2.name
00434 length = len(_x)
00435 if python3 or type(_x) == unicode:
00436 _x = _x.encode('utf-8')
00437 length = len(_x)
00438 buff.write(struct.pack('<I%ss'%length, length, _x))
00439 _x = val2
00440 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00441 _x = val1
00442 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00443 _x = val1.data
00444 length = len(_x)
00445
00446 if type(_x) in [list, tuple]:
00447 buff.write(struct.pack('<I%sB'%length, length, *_x))
00448 else:
00449 buff.write(struct.pack('<I%ss'%length, length, _x))
00450 buff.write(_struct_B.pack(val1.is_dense))
00451 _x = self
00452 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00453 _x = self.action_feedback.header.frame_id
00454 length = len(_x)
00455 if python3 or type(_x) == unicode:
00456 _x = _x.encode('utf-8')
00457 length = len(_x)
00458 buff.write(struct.pack('<I%ss'%length, length, _x))
00459 _x = self
00460 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00461 _x = self.action_feedback.status.goal_id.id
00462 length = len(_x)
00463 if python3 or type(_x) == unicode:
00464 _x = _x.encode('utf-8')
00465 length = len(_x)
00466 buff.write(struct.pack('<I%ss'%length, length, _x))
00467 buff.write(_struct_B.pack(self.action_feedback.status.status))
00468 _x = self.action_feedback.status.text
00469 length = len(_x)
00470 if python3 or type(_x) == unicode:
00471 _x = _x.encode('utf-8')
00472 length = len(_x)
00473 buff.write(struct.pack('<I%ss'%length, length, _x))
00474 except struct.error as se: self._check_types(se)
00475 except TypeError as te: self._check_types(te)
00476
00477 def deserialize(self, str):
00478 """
00479 unpack serialized message in str into this message instance
00480 :param str: byte array of serialized message, ``str``
00481 """
00482 try:
00483 if self.action_goal is None:
00484 self.action_goal = object_manipulation_msgs.msg.FindContainerActionGoal()
00485 if self.action_result is None:
00486 self.action_result = object_manipulation_msgs.msg.FindContainerActionResult()
00487 if self.action_feedback is None:
00488 self.action_feedback = object_manipulation_msgs.msg.FindContainerActionFeedback()
00489 end = 0
00490 _x = self
00491 start = end
00492 end += 12
00493 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00494 start = end
00495 end += 4
00496 (length,) = _struct_I.unpack(str[start:end])
00497 start = end
00498 end += length
00499 if python3:
00500 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00501 else:
00502 self.action_goal.header.frame_id = str[start:end]
00503 _x = self
00504 start = end
00505 end += 8
00506 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00507 start = end
00508 end += 4
00509 (length,) = _struct_I.unpack(str[start:end])
00510 start = end
00511 end += length
00512 if python3:
00513 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00514 else:
00515 self.action_goal.goal_id.id = str[start:end]
00516 _x = self
00517 start = end
00518 end += 12
00519 (_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00520 start = end
00521 end += 4
00522 (length,) = _struct_I.unpack(str[start:end])
00523 start = end
00524 end += length
00525 if python3:
00526 self.action_goal.goal.cloud.header.frame_id = str[start:end].decode('utf-8')
00527 else:
00528 self.action_goal.goal.cloud.header.frame_id = str[start:end]
00529 _x = self
00530 start = end
00531 end += 8
00532 (_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width,) = _struct_2I.unpack(str[start:end])
00533 start = end
00534 end += 4
00535 (length,) = _struct_I.unpack(str[start:end])
00536 self.action_goal.goal.cloud.fields = []
00537 for i in range(0, length):
00538 val1 = sensor_msgs.msg.PointField()
00539 start = end
00540 end += 4
00541 (length,) = _struct_I.unpack(str[start:end])
00542 start = end
00543 end += length
00544 if python3:
00545 val1.name = str[start:end].decode('utf-8')
00546 else:
00547 val1.name = str[start:end]
00548 _x = val1
00549 start = end
00550 end += 9
00551 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00552 self.action_goal.goal.cloud.fields.append(val1)
00553 _x = self
00554 start = end
00555 end += 9
00556 (_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00557 self.action_goal.goal.cloud.is_bigendian = bool(self.action_goal.goal.cloud.is_bigendian)
00558 start = end
00559 end += 4
00560 (length,) = _struct_I.unpack(str[start:end])
00561 start = end
00562 end += length
00563 if python3:
00564 self.action_goal.goal.cloud.data = str[start:end].decode('utf-8')
00565 else:
00566 self.action_goal.goal.cloud.data = str[start:end]
00567 _x = self
00568 start = end
00569 end += 13
00570 (_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.box_pose.header.seq, _x.action_goal.goal.box_pose.header.stamp.secs, _x.action_goal.goal.box_pose.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00571 self.action_goal.goal.cloud.is_dense = bool(self.action_goal.goal.cloud.is_dense)
00572 start = end
00573 end += 4
00574 (length,) = _struct_I.unpack(str[start:end])
00575 start = end
00576 end += length
00577 if python3:
00578 self.action_goal.goal.box_pose.header.frame_id = str[start:end].decode('utf-8')
00579 else:
00580 self.action_goal.goal.box_pose.header.frame_id = str[start:end]
00581 _x = self
00582 start = end
00583 end += 116
00584 (_x.action_goal.goal.box_pose.pose.position.x, _x.action_goal.goal.box_pose.pose.position.y, _x.action_goal.goal.box_pose.pose.position.z, _x.action_goal.goal.box_pose.pose.orientation.x, _x.action_goal.goal.box_pose.pose.orientation.y, _x.action_goal.goal.box_pose.pose.orientation.z, _x.action_goal.goal.box_pose.pose.orientation.w, _x.action_goal.goal.box_dims.x, _x.action_goal.goal.box_dims.y, _x.action_goal.goal.box_dims.z, _x.action_goal.goal.opening_dir.x, _x.action_goal.goal.opening_dir.y, _x.action_goal.goal.opening_dir.z, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_13d3I.unpack(str[start:end])
00585 start = end
00586 end += 4
00587 (length,) = _struct_I.unpack(str[start:end])
00588 start = end
00589 end += length
00590 if python3:
00591 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00592 else:
00593 self.action_result.header.frame_id = str[start:end]
00594 _x = self
00595 start = end
00596 end += 8
00597 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00598 start = end
00599 end += 4
00600 (length,) = _struct_I.unpack(str[start:end])
00601 start = end
00602 end += length
00603 if python3:
00604 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00605 else:
00606 self.action_result.status.goal_id.id = str[start:end]
00607 start = end
00608 end += 1
00609 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00610 start = end
00611 end += 4
00612 (length,) = _struct_I.unpack(str[start:end])
00613 start = end
00614 end += length
00615 if python3:
00616 self.action_result.status.text = str[start:end].decode('utf-8')
00617 else:
00618 self.action_result.status.text = str[start:end]
00619 _x = self
00620 start = end
00621 end += 12
00622 (_x.action_result.result.box_pose.header.seq, _x.action_result.result.box_pose.header.stamp.secs, _x.action_result.result.box_pose.header.stamp.nsecs,) = _struct_3I.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 if python3:
00629 self.action_result.result.box_pose.header.frame_id = str[start:end].decode('utf-8')
00630 else:
00631 self.action_result.result.box_pose.header.frame_id = str[start:end]
00632 _x = self
00633 start = end
00634 end += 92
00635 (_x.action_result.result.box_pose.pose.position.x, _x.action_result.result.box_pose.pose.position.y, _x.action_result.result.box_pose.pose.position.z, _x.action_result.result.box_pose.pose.orientation.x, _x.action_result.result.box_pose.pose.orientation.y, _x.action_result.result.box_pose.pose.orientation.z, _x.action_result.result.box_pose.pose.orientation.w, _x.action_result.result.box_dims.x, _x.action_result.result.box_dims.y, _x.action_result.result.box_dims.z, _x.action_result.result.contents.header.seq, _x.action_result.result.contents.header.stamp.secs, _x.action_result.result.contents.header.stamp.nsecs,) = _struct_10d3I.unpack(str[start:end])
00636 start = end
00637 end += 4
00638 (length,) = _struct_I.unpack(str[start:end])
00639 start = end
00640 end += length
00641 if python3:
00642 self.action_result.result.contents.header.frame_id = str[start:end].decode('utf-8')
00643 else:
00644 self.action_result.result.contents.header.frame_id = str[start:end]
00645 _x = self
00646 start = end
00647 end += 8
00648 (_x.action_result.result.contents.height, _x.action_result.result.contents.width,) = _struct_2I.unpack(str[start:end])
00649 start = end
00650 end += 4
00651 (length,) = _struct_I.unpack(str[start:end])
00652 self.action_result.result.contents.fields = []
00653 for i in range(0, length):
00654 val1 = sensor_msgs.msg.PointField()
00655 start = end
00656 end += 4
00657 (length,) = _struct_I.unpack(str[start:end])
00658 start = end
00659 end += length
00660 if python3:
00661 val1.name = str[start:end].decode('utf-8')
00662 else:
00663 val1.name = str[start:end]
00664 _x = val1
00665 start = end
00666 end += 9
00667 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00668 self.action_result.result.contents.fields.append(val1)
00669 _x = self
00670 start = end
00671 end += 9
00672 (_x.action_result.result.contents.is_bigendian, _x.action_result.result.contents.point_step, _x.action_result.result.contents.row_step,) = _struct_B2I.unpack(str[start:end])
00673 self.action_result.result.contents.is_bigendian = bool(self.action_result.result.contents.is_bigendian)
00674 start = end
00675 end += 4
00676 (length,) = _struct_I.unpack(str[start:end])
00677 start = end
00678 end += length
00679 if python3:
00680 self.action_result.result.contents.data = str[start:end].decode('utf-8')
00681 else:
00682 self.action_result.result.contents.data = str[start:end]
00683 _x = self
00684 start = end
00685 end += 13
00686 (_x.action_result.result.contents.is_dense, _x.action_result.result.container.header.seq, _x.action_result.result.container.header.stamp.secs, _x.action_result.result.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00687 self.action_result.result.contents.is_dense = bool(self.action_result.result.contents.is_dense)
00688 start = end
00689 end += 4
00690 (length,) = _struct_I.unpack(str[start:end])
00691 start = end
00692 end += length
00693 if python3:
00694 self.action_result.result.container.header.frame_id = str[start:end].decode('utf-8')
00695 else:
00696 self.action_result.result.container.header.frame_id = str[start:end]
00697 _x = self
00698 start = end
00699 end += 8
00700 (_x.action_result.result.container.height, _x.action_result.result.container.width,) = _struct_2I.unpack(str[start:end])
00701 start = end
00702 end += 4
00703 (length,) = _struct_I.unpack(str[start:end])
00704 self.action_result.result.container.fields = []
00705 for i in range(0, length):
00706 val1 = sensor_msgs.msg.PointField()
00707 start = end
00708 end += 4
00709 (length,) = _struct_I.unpack(str[start:end])
00710 start = end
00711 end += length
00712 if python3:
00713 val1.name = str[start:end].decode('utf-8')
00714 else:
00715 val1.name = str[start:end]
00716 _x = val1
00717 start = end
00718 end += 9
00719 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00720 self.action_result.result.container.fields.append(val1)
00721 _x = self
00722 start = end
00723 end += 9
00724 (_x.action_result.result.container.is_bigendian, _x.action_result.result.container.point_step, _x.action_result.result.container.row_step,) = _struct_B2I.unpack(str[start:end])
00725 self.action_result.result.container.is_bigendian = bool(self.action_result.result.container.is_bigendian)
00726 start = end
00727 end += 4
00728 (length,) = _struct_I.unpack(str[start:end])
00729 start = end
00730 end += length
00731 if python3:
00732 self.action_result.result.container.data = str[start:end].decode('utf-8')
00733 else:
00734 self.action_result.result.container.data = str[start:end]
00735 start = end
00736 end += 1
00737 (self.action_result.result.container.is_dense,) = _struct_B.unpack(str[start:end])
00738 self.action_result.result.container.is_dense = bool(self.action_result.result.container.is_dense)
00739 start = end
00740 end += 4
00741 (length,) = _struct_I.unpack(str[start:end])
00742 self.action_result.result.clusters = []
00743 for i in range(0, length):
00744 val1 = sensor_msgs.msg.PointCloud2()
00745 _v3 = val1.header
00746 start = end
00747 end += 4
00748 (_v3.seq,) = _struct_I.unpack(str[start:end])
00749 _v4 = _v3.stamp
00750 _x = _v4
00751 start = end
00752 end += 8
00753 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00754 start = end
00755 end += 4
00756 (length,) = _struct_I.unpack(str[start:end])
00757 start = end
00758 end += length
00759 if python3:
00760 _v3.frame_id = str[start:end].decode('utf-8')
00761 else:
00762 _v3.frame_id = str[start:end]
00763 _x = val1
00764 start = end
00765 end += 8
00766 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00767 start = end
00768 end += 4
00769 (length,) = _struct_I.unpack(str[start:end])
00770 val1.fields = []
00771 for i in range(0, length):
00772 val2 = sensor_msgs.msg.PointField()
00773 start = end
00774 end += 4
00775 (length,) = _struct_I.unpack(str[start:end])
00776 start = end
00777 end += length
00778 if python3:
00779 val2.name = str[start:end].decode('utf-8')
00780 else:
00781 val2.name = str[start:end]
00782 _x = val2
00783 start = end
00784 end += 9
00785 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00786 val1.fields.append(val2)
00787 _x = val1
00788 start = end
00789 end += 9
00790 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00791 val1.is_bigendian = bool(val1.is_bigendian)
00792 start = end
00793 end += 4
00794 (length,) = _struct_I.unpack(str[start:end])
00795 start = end
00796 end += length
00797 if python3:
00798 val1.data = str[start:end].decode('utf-8')
00799 else:
00800 val1.data = str[start:end]
00801 start = end
00802 end += 1
00803 (val1.is_dense,) = _struct_B.unpack(str[start:end])
00804 val1.is_dense = bool(val1.is_dense)
00805 self.action_result.result.clusters.append(val1)
00806 _x = self
00807 start = end
00808 end += 12
00809 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00810 start = end
00811 end += 4
00812 (length,) = _struct_I.unpack(str[start:end])
00813 start = end
00814 end += length
00815 if python3:
00816 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00817 else:
00818 self.action_feedback.header.frame_id = str[start:end]
00819 _x = self
00820 start = end
00821 end += 8
00822 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00823 start = end
00824 end += 4
00825 (length,) = _struct_I.unpack(str[start:end])
00826 start = end
00827 end += length
00828 if python3:
00829 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00830 else:
00831 self.action_feedback.status.goal_id.id = str[start:end]
00832 start = end
00833 end += 1
00834 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00835 start = end
00836 end += 4
00837 (length,) = _struct_I.unpack(str[start:end])
00838 start = end
00839 end += length
00840 if python3:
00841 self.action_feedback.status.text = str[start:end].decode('utf-8')
00842 else:
00843 self.action_feedback.status.text = str[start:end]
00844 return self
00845 except struct.error as e:
00846 raise genpy.DeserializationError(e)
00847
00848
00849 def serialize_numpy(self, buff, numpy):
00850 """
00851 serialize message with numpy array types into buffer
00852 :param buff: buffer, ``StringIO``
00853 :param numpy: numpy python module
00854 """
00855 try:
00856 _x = self
00857 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00858 _x = self.action_goal.header.frame_id
00859 length = len(_x)
00860 if python3 or type(_x) == unicode:
00861 _x = _x.encode('utf-8')
00862 length = len(_x)
00863 buff.write(struct.pack('<I%ss'%length, length, _x))
00864 _x = self
00865 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00866 _x = self.action_goal.goal_id.id
00867 length = len(_x)
00868 if python3 or type(_x) == unicode:
00869 _x = _x.encode('utf-8')
00870 length = len(_x)
00871 buff.write(struct.pack('<I%ss'%length, length, _x))
00872 _x = self
00873 buff.write(_struct_3I.pack(_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs))
00874 _x = self.action_goal.goal.cloud.header.frame_id
00875 length = len(_x)
00876 if python3 or type(_x) == unicode:
00877 _x = _x.encode('utf-8')
00878 length = len(_x)
00879 buff.write(struct.pack('<I%ss'%length, length, _x))
00880 _x = self
00881 buff.write(_struct_2I.pack(_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width))
00882 length = len(self.action_goal.goal.cloud.fields)
00883 buff.write(_struct_I.pack(length))
00884 for val1 in self.action_goal.goal.cloud.fields:
00885 _x = val1.name
00886 length = len(_x)
00887 if python3 or type(_x) == unicode:
00888 _x = _x.encode('utf-8')
00889 length = len(_x)
00890 buff.write(struct.pack('<I%ss'%length, length, _x))
00891 _x = val1
00892 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00893 _x = self
00894 buff.write(_struct_B2I.pack(_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step))
00895 _x = self.action_goal.goal.cloud.data
00896 length = len(_x)
00897
00898 if type(_x) in [list, tuple]:
00899 buff.write(struct.pack('<I%sB'%length, length, *_x))
00900 else:
00901 buff.write(struct.pack('<I%ss'%length, length, _x))
00902 _x = self
00903 buff.write(_struct_B3I.pack(_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.box_pose.header.seq, _x.action_goal.goal.box_pose.header.stamp.secs, _x.action_goal.goal.box_pose.header.stamp.nsecs))
00904 _x = self.action_goal.goal.box_pose.header.frame_id
00905 length = len(_x)
00906 if python3 or type(_x) == unicode:
00907 _x = _x.encode('utf-8')
00908 length = len(_x)
00909 buff.write(struct.pack('<I%ss'%length, length, _x))
00910 _x = self
00911 buff.write(_struct_13d3I.pack(_x.action_goal.goal.box_pose.pose.position.x, _x.action_goal.goal.box_pose.pose.position.y, _x.action_goal.goal.box_pose.pose.position.z, _x.action_goal.goal.box_pose.pose.orientation.x, _x.action_goal.goal.box_pose.pose.orientation.y, _x.action_goal.goal.box_pose.pose.orientation.z, _x.action_goal.goal.box_pose.pose.orientation.w, _x.action_goal.goal.box_dims.x, _x.action_goal.goal.box_dims.y, _x.action_goal.goal.box_dims.z, _x.action_goal.goal.opening_dir.x, _x.action_goal.goal.opening_dir.y, _x.action_goal.goal.opening_dir.z, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00912 _x = self.action_result.header.frame_id
00913 length = len(_x)
00914 if python3 or type(_x) == unicode:
00915 _x = _x.encode('utf-8')
00916 length = len(_x)
00917 buff.write(struct.pack('<I%ss'%length, length, _x))
00918 _x = self
00919 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00920 _x = self.action_result.status.goal_id.id
00921 length = len(_x)
00922 if python3 or type(_x) == unicode:
00923 _x = _x.encode('utf-8')
00924 length = len(_x)
00925 buff.write(struct.pack('<I%ss'%length, length, _x))
00926 buff.write(_struct_B.pack(self.action_result.status.status))
00927 _x = self.action_result.status.text
00928 length = len(_x)
00929 if python3 or type(_x) == unicode:
00930 _x = _x.encode('utf-8')
00931 length = len(_x)
00932 buff.write(struct.pack('<I%ss'%length, length, _x))
00933 _x = self
00934 buff.write(_struct_3I.pack(_x.action_result.result.box_pose.header.seq, _x.action_result.result.box_pose.header.stamp.secs, _x.action_result.result.box_pose.header.stamp.nsecs))
00935 _x = self.action_result.result.box_pose.header.frame_id
00936 length = len(_x)
00937 if python3 or type(_x) == unicode:
00938 _x = _x.encode('utf-8')
00939 length = len(_x)
00940 buff.write(struct.pack('<I%ss'%length, length, _x))
00941 _x = self
00942 buff.write(_struct_10d3I.pack(_x.action_result.result.box_pose.pose.position.x, _x.action_result.result.box_pose.pose.position.y, _x.action_result.result.box_pose.pose.position.z, _x.action_result.result.box_pose.pose.orientation.x, _x.action_result.result.box_pose.pose.orientation.y, _x.action_result.result.box_pose.pose.orientation.z, _x.action_result.result.box_pose.pose.orientation.w, _x.action_result.result.box_dims.x, _x.action_result.result.box_dims.y, _x.action_result.result.box_dims.z, _x.action_result.result.contents.header.seq, _x.action_result.result.contents.header.stamp.secs, _x.action_result.result.contents.header.stamp.nsecs))
00943 _x = self.action_result.result.contents.header.frame_id
00944 length = len(_x)
00945 if python3 or type(_x) == unicode:
00946 _x = _x.encode('utf-8')
00947 length = len(_x)
00948 buff.write(struct.pack('<I%ss'%length, length, _x))
00949 _x = self
00950 buff.write(_struct_2I.pack(_x.action_result.result.contents.height, _x.action_result.result.contents.width))
00951 length = len(self.action_result.result.contents.fields)
00952 buff.write(_struct_I.pack(length))
00953 for val1 in self.action_result.result.contents.fields:
00954 _x = val1.name
00955 length = len(_x)
00956 if python3 or type(_x) == unicode:
00957 _x = _x.encode('utf-8')
00958 length = len(_x)
00959 buff.write(struct.pack('<I%ss'%length, length, _x))
00960 _x = val1
00961 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00962 _x = self
00963 buff.write(_struct_B2I.pack(_x.action_result.result.contents.is_bigendian, _x.action_result.result.contents.point_step, _x.action_result.result.contents.row_step))
00964 _x = self.action_result.result.contents.data
00965 length = len(_x)
00966
00967 if type(_x) in [list, tuple]:
00968 buff.write(struct.pack('<I%sB'%length, length, *_x))
00969 else:
00970 buff.write(struct.pack('<I%ss'%length, length, _x))
00971 _x = self
00972 buff.write(_struct_B3I.pack(_x.action_result.result.contents.is_dense, _x.action_result.result.container.header.seq, _x.action_result.result.container.header.stamp.secs, _x.action_result.result.container.header.stamp.nsecs))
00973 _x = self.action_result.result.container.header.frame_id
00974 length = len(_x)
00975 if python3 or type(_x) == unicode:
00976 _x = _x.encode('utf-8')
00977 length = len(_x)
00978 buff.write(struct.pack('<I%ss'%length, length, _x))
00979 _x = self
00980 buff.write(_struct_2I.pack(_x.action_result.result.container.height, _x.action_result.result.container.width))
00981 length = len(self.action_result.result.container.fields)
00982 buff.write(_struct_I.pack(length))
00983 for val1 in self.action_result.result.container.fields:
00984 _x = val1.name
00985 length = len(_x)
00986 if python3 or type(_x) == unicode:
00987 _x = _x.encode('utf-8')
00988 length = len(_x)
00989 buff.write(struct.pack('<I%ss'%length, length, _x))
00990 _x = val1
00991 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00992 _x = self
00993 buff.write(_struct_B2I.pack(_x.action_result.result.container.is_bigendian, _x.action_result.result.container.point_step, _x.action_result.result.container.row_step))
00994 _x = self.action_result.result.container.data
00995 length = len(_x)
00996
00997 if type(_x) in [list, tuple]:
00998 buff.write(struct.pack('<I%sB'%length, length, *_x))
00999 else:
01000 buff.write(struct.pack('<I%ss'%length, length, _x))
01001 buff.write(_struct_B.pack(self.action_result.result.container.is_dense))
01002 length = len(self.action_result.result.clusters)
01003 buff.write(_struct_I.pack(length))
01004 for val1 in self.action_result.result.clusters:
01005 _v5 = val1.header
01006 buff.write(_struct_I.pack(_v5.seq))
01007 _v6 = _v5.stamp
01008 _x = _v6
01009 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01010 _x = _v5.frame_id
01011 length = len(_x)
01012 if python3 or type(_x) == unicode:
01013 _x = _x.encode('utf-8')
01014 length = len(_x)
01015 buff.write(struct.pack('<I%ss'%length, length, _x))
01016 _x = val1
01017 buff.write(_struct_2I.pack(_x.height, _x.width))
01018 length = len(val1.fields)
01019 buff.write(_struct_I.pack(length))
01020 for val2 in val1.fields:
01021 _x = val2.name
01022 length = len(_x)
01023 if python3 or type(_x) == unicode:
01024 _x = _x.encode('utf-8')
01025 length = len(_x)
01026 buff.write(struct.pack('<I%ss'%length, length, _x))
01027 _x = val2
01028 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01029 _x = val1
01030 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01031 _x = val1.data
01032 length = len(_x)
01033
01034 if type(_x) in [list, tuple]:
01035 buff.write(struct.pack('<I%sB'%length, length, *_x))
01036 else:
01037 buff.write(struct.pack('<I%ss'%length, length, _x))
01038 buff.write(_struct_B.pack(val1.is_dense))
01039 _x = self
01040 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
01041 _x = self.action_feedback.header.frame_id
01042 length = len(_x)
01043 if python3 or type(_x) == unicode:
01044 _x = _x.encode('utf-8')
01045 length = len(_x)
01046 buff.write(struct.pack('<I%ss'%length, length, _x))
01047 _x = self
01048 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
01049 _x = self.action_feedback.status.goal_id.id
01050 length = len(_x)
01051 if python3 or type(_x) == unicode:
01052 _x = _x.encode('utf-8')
01053 length = len(_x)
01054 buff.write(struct.pack('<I%ss'%length, length, _x))
01055 buff.write(_struct_B.pack(self.action_feedback.status.status))
01056 _x = self.action_feedback.status.text
01057 length = len(_x)
01058 if python3 or type(_x) == unicode:
01059 _x = _x.encode('utf-8')
01060 length = len(_x)
01061 buff.write(struct.pack('<I%ss'%length, length, _x))
01062 except struct.error as se: self._check_types(se)
01063 except TypeError as te: self._check_types(te)
01064
01065 def deserialize_numpy(self, str, numpy):
01066 """
01067 unpack serialized message in str into this message instance using numpy for array types
01068 :param str: byte array of serialized message, ``str``
01069 :param numpy: numpy python module
01070 """
01071 try:
01072 if self.action_goal is None:
01073 self.action_goal = object_manipulation_msgs.msg.FindContainerActionGoal()
01074 if self.action_result is None:
01075 self.action_result = object_manipulation_msgs.msg.FindContainerActionResult()
01076 if self.action_feedback is None:
01077 self.action_feedback = object_manipulation_msgs.msg.FindContainerActionFeedback()
01078 end = 0
01079 _x = self
01080 start = end
01081 end += 12
01082 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01083 start = end
01084 end += 4
01085 (length,) = _struct_I.unpack(str[start:end])
01086 start = end
01087 end += length
01088 if python3:
01089 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
01090 else:
01091 self.action_goal.header.frame_id = str[start:end]
01092 _x = self
01093 start = end
01094 end += 8
01095 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01096 start = end
01097 end += 4
01098 (length,) = _struct_I.unpack(str[start:end])
01099 start = end
01100 end += length
01101 if python3:
01102 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
01103 else:
01104 self.action_goal.goal_id.id = str[start:end]
01105 _x = self
01106 start = end
01107 end += 12
01108 (_x.action_goal.goal.cloud.header.seq, _x.action_goal.goal.cloud.header.stamp.secs, _x.action_goal.goal.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01109 start = end
01110 end += 4
01111 (length,) = _struct_I.unpack(str[start:end])
01112 start = end
01113 end += length
01114 if python3:
01115 self.action_goal.goal.cloud.header.frame_id = str[start:end].decode('utf-8')
01116 else:
01117 self.action_goal.goal.cloud.header.frame_id = str[start:end]
01118 _x = self
01119 start = end
01120 end += 8
01121 (_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width,) = _struct_2I.unpack(str[start:end])
01122 start = end
01123 end += 4
01124 (length,) = _struct_I.unpack(str[start:end])
01125 self.action_goal.goal.cloud.fields = []
01126 for i in range(0, length):
01127 val1 = sensor_msgs.msg.PointField()
01128 start = end
01129 end += 4
01130 (length,) = _struct_I.unpack(str[start:end])
01131 start = end
01132 end += length
01133 if python3:
01134 val1.name = str[start:end].decode('utf-8')
01135 else:
01136 val1.name = str[start:end]
01137 _x = val1
01138 start = end
01139 end += 9
01140 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01141 self.action_goal.goal.cloud.fields.append(val1)
01142 _x = self
01143 start = end
01144 end += 9
01145 (_x.action_goal.goal.cloud.is_bigendian, _x.action_goal.goal.cloud.point_step, _x.action_goal.goal.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01146 self.action_goal.goal.cloud.is_bigendian = bool(self.action_goal.goal.cloud.is_bigendian)
01147 start = end
01148 end += 4
01149 (length,) = _struct_I.unpack(str[start:end])
01150 start = end
01151 end += length
01152 if python3:
01153 self.action_goal.goal.cloud.data = str[start:end].decode('utf-8')
01154 else:
01155 self.action_goal.goal.cloud.data = str[start:end]
01156 _x = self
01157 start = end
01158 end += 13
01159 (_x.action_goal.goal.cloud.is_dense, _x.action_goal.goal.box_pose.header.seq, _x.action_goal.goal.box_pose.header.stamp.secs, _x.action_goal.goal.box_pose.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01160 self.action_goal.goal.cloud.is_dense = bool(self.action_goal.goal.cloud.is_dense)
01161 start = end
01162 end += 4
01163 (length,) = _struct_I.unpack(str[start:end])
01164 start = end
01165 end += length
01166 if python3:
01167 self.action_goal.goal.box_pose.header.frame_id = str[start:end].decode('utf-8')
01168 else:
01169 self.action_goal.goal.box_pose.header.frame_id = str[start:end]
01170 _x = self
01171 start = end
01172 end += 116
01173 (_x.action_goal.goal.box_pose.pose.position.x, _x.action_goal.goal.box_pose.pose.position.y, _x.action_goal.goal.box_pose.pose.position.z, _x.action_goal.goal.box_pose.pose.orientation.x, _x.action_goal.goal.box_pose.pose.orientation.y, _x.action_goal.goal.box_pose.pose.orientation.z, _x.action_goal.goal.box_pose.pose.orientation.w, _x.action_goal.goal.box_dims.x, _x.action_goal.goal.box_dims.y, _x.action_goal.goal.box_dims.z, _x.action_goal.goal.opening_dir.x, _x.action_goal.goal.opening_dir.y, _x.action_goal.goal.opening_dir.z, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_13d3I.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 if python3:
01180 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01181 else:
01182 self.action_result.header.frame_id = str[start:end]
01183 _x = self
01184 start = end
01185 end += 8
01186 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01187 start = end
01188 end += 4
01189 (length,) = _struct_I.unpack(str[start:end])
01190 start = end
01191 end += length
01192 if python3:
01193 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01194 else:
01195 self.action_result.status.goal_id.id = str[start:end]
01196 start = end
01197 end += 1
01198 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01199 start = end
01200 end += 4
01201 (length,) = _struct_I.unpack(str[start:end])
01202 start = end
01203 end += length
01204 if python3:
01205 self.action_result.status.text = str[start:end].decode('utf-8')
01206 else:
01207 self.action_result.status.text = str[start:end]
01208 _x = self
01209 start = end
01210 end += 12
01211 (_x.action_result.result.box_pose.header.seq, _x.action_result.result.box_pose.header.stamp.secs, _x.action_result.result.box_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01212 start = end
01213 end += 4
01214 (length,) = _struct_I.unpack(str[start:end])
01215 start = end
01216 end += length
01217 if python3:
01218 self.action_result.result.box_pose.header.frame_id = str[start:end].decode('utf-8')
01219 else:
01220 self.action_result.result.box_pose.header.frame_id = str[start:end]
01221 _x = self
01222 start = end
01223 end += 92
01224 (_x.action_result.result.box_pose.pose.position.x, _x.action_result.result.box_pose.pose.position.y, _x.action_result.result.box_pose.pose.position.z, _x.action_result.result.box_pose.pose.orientation.x, _x.action_result.result.box_pose.pose.orientation.y, _x.action_result.result.box_pose.pose.orientation.z, _x.action_result.result.box_pose.pose.orientation.w, _x.action_result.result.box_dims.x, _x.action_result.result.box_dims.y, _x.action_result.result.box_dims.z, _x.action_result.result.contents.header.seq, _x.action_result.result.contents.header.stamp.secs, _x.action_result.result.contents.header.stamp.nsecs,) = _struct_10d3I.unpack(str[start:end])
01225 start = end
01226 end += 4
01227 (length,) = _struct_I.unpack(str[start:end])
01228 start = end
01229 end += length
01230 if python3:
01231 self.action_result.result.contents.header.frame_id = str[start:end].decode('utf-8')
01232 else:
01233 self.action_result.result.contents.header.frame_id = str[start:end]
01234 _x = self
01235 start = end
01236 end += 8
01237 (_x.action_result.result.contents.height, _x.action_result.result.contents.width,) = _struct_2I.unpack(str[start:end])
01238 start = end
01239 end += 4
01240 (length,) = _struct_I.unpack(str[start:end])
01241 self.action_result.result.contents.fields = []
01242 for i in range(0, length):
01243 val1 = sensor_msgs.msg.PointField()
01244 start = end
01245 end += 4
01246 (length,) = _struct_I.unpack(str[start:end])
01247 start = end
01248 end += length
01249 if python3:
01250 val1.name = str[start:end].decode('utf-8')
01251 else:
01252 val1.name = str[start:end]
01253 _x = val1
01254 start = end
01255 end += 9
01256 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01257 self.action_result.result.contents.fields.append(val1)
01258 _x = self
01259 start = end
01260 end += 9
01261 (_x.action_result.result.contents.is_bigendian, _x.action_result.result.contents.point_step, _x.action_result.result.contents.row_step,) = _struct_B2I.unpack(str[start:end])
01262 self.action_result.result.contents.is_bigendian = bool(self.action_result.result.contents.is_bigendian)
01263 start = end
01264 end += 4
01265 (length,) = _struct_I.unpack(str[start:end])
01266 start = end
01267 end += length
01268 if python3:
01269 self.action_result.result.contents.data = str[start:end].decode('utf-8')
01270 else:
01271 self.action_result.result.contents.data = str[start:end]
01272 _x = self
01273 start = end
01274 end += 13
01275 (_x.action_result.result.contents.is_dense, _x.action_result.result.container.header.seq, _x.action_result.result.container.header.stamp.secs, _x.action_result.result.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01276 self.action_result.result.contents.is_dense = bool(self.action_result.result.contents.is_dense)
01277 start = end
01278 end += 4
01279 (length,) = _struct_I.unpack(str[start:end])
01280 start = end
01281 end += length
01282 if python3:
01283 self.action_result.result.container.header.frame_id = str[start:end].decode('utf-8')
01284 else:
01285 self.action_result.result.container.header.frame_id = str[start:end]
01286 _x = self
01287 start = end
01288 end += 8
01289 (_x.action_result.result.container.height, _x.action_result.result.container.width,) = _struct_2I.unpack(str[start:end])
01290 start = end
01291 end += 4
01292 (length,) = _struct_I.unpack(str[start:end])
01293 self.action_result.result.container.fields = []
01294 for i in range(0, length):
01295 val1 = sensor_msgs.msg.PointField()
01296 start = end
01297 end += 4
01298 (length,) = _struct_I.unpack(str[start:end])
01299 start = end
01300 end += length
01301 if python3:
01302 val1.name = str[start:end].decode('utf-8')
01303 else:
01304 val1.name = str[start:end]
01305 _x = val1
01306 start = end
01307 end += 9
01308 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01309 self.action_result.result.container.fields.append(val1)
01310 _x = self
01311 start = end
01312 end += 9
01313 (_x.action_result.result.container.is_bigendian, _x.action_result.result.container.point_step, _x.action_result.result.container.row_step,) = _struct_B2I.unpack(str[start:end])
01314 self.action_result.result.container.is_bigendian = bool(self.action_result.result.container.is_bigendian)
01315 start = end
01316 end += 4
01317 (length,) = _struct_I.unpack(str[start:end])
01318 start = end
01319 end += length
01320 if python3:
01321 self.action_result.result.container.data = str[start:end].decode('utf-8')
01322 else:
01323 self.action_result.result.container.data = str[start:end]
01324 start = end
01325 end += 1
01326 (self.action_result.result.container.is_dense,) = _struct_B.unpack(str[start:end])
01327 self.action_result.result.container.is_dense = bool(self.action_result.result.container.is_dense)
01328 start = end
01329 end += 4
01330 (length,) = _struct_I.unpack(str[start:end])
01331 self.action_result.result.clusters = []
01332 for i in range(0, length):
01333 val1 = sensor_msgs.msg.PointCloud2()
01334 _v7 = val1.header
01335 start = end
01336 end += 4
01337 (_v7.seq,) = _struct_I.unpack(str[start:end])
01338 _v8 = _v7.stamp
01339 _x = _v8
01340 start = end
01341 end += 8
01342 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01343 start = end
01344 end += 4
01345 (length,) = _struct_I.unpack(str[start:end])
01346 start = end
01347 end += length
01348 if python3:
01349 _v7.frame_id = str[start:end].decode('utf-8')
01350 else:
01351 _v7.frame_id = str[start:end]
01352 _x = val1
01353 start = end
01354 end += 8
01355 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01356 start = end
01357 end += 4
01358 (length,) = _struct_I.unpack(str[start:end])
01359 val1.fields = []
01360 for i in range(0, length):
01361 val2 = sensor_msgs.msg.PointField()
01362 start = end
01363 end += 4
01364 (length,) = _struct_I.unpack(str[start:end])
01365 start = end
01366 end += length
01367 if python3:
01368 val2.name = str[start:end].decode('utf-8')
01369 else:
01370 val2.name = str[start:end]
01371 _x = val2
01372 start = end
01373 end += 9
01374 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01375 val1.fields.append(val2)
01376 _x = val1
01377 start = end
01378 end += 9
01379 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01380 val1.is_bigendian = bool(val1.is_bigendian)
01381 start = end
01382 end += 4
01383 (length,) = _struct_I.unpack(str[start:end])
01384 start = end
01385 end += length
01386 if python3:
01387 val1.data = str[start:end].decode('utf-8')
01388 else:
01389 val1.data = str[start:end]
01390 start = end
01391 end += 1
01392 (val1.is_dense,) = _struct_B.unpack(str[start:end])
01393 val1.is_dense = bool(val1.is_dense)
01394 self.action_result.result.clusters.append(val1)
01395 _x = self
01396 start = end
01397 end += 12
01398 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01399 start = end
01400 end += 4
01401 (length,) = _struct_I.unpack(str[start:end])
01402 start = end
01403 end += length
01404 if python3:
01405 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01406 else:
01407 self.action_feedback.header.frame_id = str[start:end]
01408 _x = self
01409 start = end
01410 end += 8
01411 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01412 start = end
01413 end += 4
01414 (length,) = _struct_I.unpack(str[start:end])
01415 start = end
01416 end += length
01417 if python3:
01418 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01419 else:
01420 self.action_feedback.status.goal_id.id = str[start:end]
01421 start = end
01422 end += 1
01423 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01424 start = end
01425 end += 4
01426 (length,) = _struct_I.unpack(str[start:end])
01427 start = end
01428 end += length
01429 if python3:
01430 self.action_feedback.status.text = str[start:end].decode('utf-8')
01431 else:
01432 self.action_feedback.status.text = str[start:end]
01433 return self
01434 except struct.error as e:
01435 raise genpy.DeserializationError(e)
01436
01437 _struct_I = genpy.struct_I
01438 _struct_IBI = struct.Struct("<IBI")
01439 _struct_B = struct.Struct("<B")
01440 _struct_10d3I = struct.Struct("<10d3I")
01441 _struct_13d3I = struct.Struct("<13d3I")
01442 _struct_3I = struct.Struct("<3I")
01443 _struct_B3I = struct.Struct("<B3I")
01444 _struct_B2I = struct.Struct("<B2I")
01445 _struct_2I = struct.Struct("<2I")