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(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00475 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
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 self.action_goal.goal.cloud.data = str[start:end]
00564 _x = self
00565 start = end
00566 end += 13
00567 (_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])
00568 self.action_goal.goal.cloud.is_dense = bool(self.action_goal.goal.cloud.is_dense)
00569 start = end
00570 end += 4
00571 (length,) = _struct_I.unpack(str[start:end])
00572 start = end
00573 end += length
00574 if python3:
00575 self.action_goal.goal.box_pose.header.frame_id = str[start:end].decode('utf-8')
00576 else:
00577 self.action_goal.goal.box_pose.header.frame_id = str[start:end]
00578 _x = self
00579 start = end
00580 end += 116
00581 (_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])
00582 start = end
00583 end += 4
00584 (length,) = _struct_I.unpack(str[start:end])
00585 start = end
00586 end += length
00587 if python3:
00588 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00589 else:
00590 self.action_result.header.frame_id = str[start:end]
00591 _x = self
00592 start = end
00593 end += 8
00594 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00595 start = end
00596 end += 4
00597 (length,) = _struct_I.unpack(str[start:end])
00598 start = end
00599 end += length
00600 if python3:
00601 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00602 else:
00603 self.action_result.status.goal_id.id = str[start:end]
00604 start = end
00605 end += 1
00606 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00607 start = end
00608 end += 4
00609 (length,) = _struct_I.unpack(str[start:end])
00610 start = end
00611 end += length
00612 if python3:
00613 self.action_result.status.text = str[start:end].decode('utf-8')
00614 else:
00615 self.action_result.status.text = str[start:end]
00616 _x = self
00617 start = end
00618 end += 12
00619 (_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])
00620 start = end
00621 end += 4
00622 (length,) = _struct_I.unpack(str[start:end])
00623 start = end
00624 end += length
00625 if python3:
00626 self.action_result.result.box_pose.header.frame_id = str[start:end].decode('utf-8')
00627 else:
00628 self.action_result.result.box_pose.header.frame_id = str[start:end]
00629 _x = self
00630 start = end
00631 end += 92
00632 (_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])
00633 start = end
00634 end += 4
00635 (length,) = _struct_I.unpack(str[start:end])
00636 start = end
00637 end += length
00638 if python3:
00639 self.action_result.result.contents.header.frame_id = str[start:end].decode('utf-8')
00640 else:
00641 self.action_result.result.contents.header.frame_id = str[start:end]
00642 _x = self
00643 start = end
00644 end += 8
00645 (_x.action_result.result.contents.height, _x.action_result.result.contents.width,) = _struct_2I.unpack(str[start:end])
00646 start = end
00647 end += 4
00648 (length,) = _struct_I.unpack(str[start:end])
00649 self.action_result.result.contents.fields = []
00650 for i in range(0, length):
00651 val1 = sensor_msgs.msg.PointField()
00652 start = end
00653 end += 4
00654 (length,) = _struct_I.unpack(str[start:end])
00655 start = end
00656 end += length
00657 if python3:
00658 val1.name = str[start:end].decode('utf-8')
00659 else:
00660 val1.name = str[start:end]
00661 _x = val1
00662 start = end
00663 end += 9
00664 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00665 self.action_result.result.contents.fields.append(val1)
00666 _x = self
00667 start = end
00668 end += 9
00669 (_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])
00670 self.action_result.result.contents.is_bigendian = bool(self.action_result.result.contents.is_bigendian)
00671 start = end
00672 end += 4
00673 (length,) = _struct_I.unpack(str[start:end])
00674 start = end
00675 end += length
00676 self.action_result.result.contents.data = str[start:end]
00677 _x = self
00678 start = end
00679 end += 13
00680 (_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])
00681 self.action_result.result.contents.is_dense = bool(self.action_result.result.contents.is_dense)
00682 start = end
00683 end += 4
00684 (length,) = _struct_I.unpack(str[start:end])
00685 start = end
00686 end += length
00687 if python3:
00688 self.action_result.result.container.header.frame_id = str[start:end].decode('utf-8')
00689 else:
00690 self.action_result.result.container.header.frame_id = str[start:end]
00691 _x = self
00692 start = end
00693 end += 8
00694 (_x.action_result.result.container.height, _x.action_result.result.container.width,) = _struct_2I.unpack(str[start:end])
00695 start = end
00696 end += 4
00697 (length,) = _struct_I.unpack(str[start:end])
00698 self.action_result.result.container.fields = []
00699 for i in range(0, length):
00700 val1 = sensor_msgs.msg.PointField()
00701 start = end
00702 end += 4
00703 (length,) = _struct_I.unpack(str[start:end])
00704 start = end
00705 end += length
00706 if python3:
00707 val1.name = str[start:end].decode('utf-8')
00708 else:
00709 val1.name = str[start:end]
00710 _x = val1
00711 start = end
00712 end += 9
00713 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00714 self.action_result.result.container.fields.append(val1)
00715 _x = self
00716 start = end
00717 end += 9
00718 (_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])
00719 self.action_result.result.container.is_bigendian = bool(self.action_result.result.container.is_bigendian)
00720 start = end
00721 end += 4
00722 (length,) = _struct_I.unpack(str[start:end])
00723 start = end
00724 end += length
00725 self.action_result.result.container.data = str[start:end]
00726 start = end
00727 end += 1
00728 (self.action_result.result.container.is_dense,) = _struct_B.unpack(str[start:end])
00729 self.action_result.result.container.is_dense = bool(self.action_result.result.container.is_dense)
00730 start = end
00731 end += 4
00732 (length,) = _struct_I.unpack(str[start:end])
00733 self.action_result.result.clusters = []
00734 for i in range(0, length):
00735 val1 = sensor_msgs.msg.PointCloud2()
00736 _v3 = val1.header
00737 start = end
00738 end += 4
00739 (_v3.seq,) = _struct_I.unpack(str[start:end])
00740 _v4 = _v3.stamp
00741 _x = _v4
00742 start = end
00743 end += 8
00744 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00745 start = end
00746 end += 4
00747 (length,) = _struct_I.unpack(str[start:end])
00748 start = end
00749 end += length
00750 if python3:
00751 _v3.frame_id = str[start:end].decode('utf-8')
00752 else:
00753 _v3.frame_id = str[start:end]
00754 _x = val1
00755 start = end
00756 end += 8
00757 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00758 start = end
00759 end += 4
00760 (length,) = _struct_I.unpack(str[start:end])
00761 val1.fields = []
00762 for i in range(0, length):
00763 val2 = sensor_msgs.msg.PointField()
00764 start = end
00765 end += 4
00766 (length,) = _struct_I.unpack(str[start:end])
00767 start = end
00768 end += length
00769 if python3:
00770 val2.name = str[start:end].decode('utf-8')
00771 else:
00772 val2.name = str[start:end]
00773 _x = val2
00774 start = end
00775 end += 9
00776 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00777 val1.fields.append(val2)
00778 _x = val1
00779 start = end
00780 end += 9
00781 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00782 val1.is_bigendian = bool(val1.is_bigendian)
00783 start = end
00784 end += 4
00785 (length,) = _struct_I.unpack(str[start:end])
00786 start = end
00787 end += length
00788 val1.data = str[start:end]
00789 start = end
00790 end += 1
00791 (val1.is_dense,) = _struct_B.unpack(str[start:end])
00792 val1.is_dense = bool(val1.is_dense)
00793 self.action_result.result.clusters.append(val1)
00794 _x = self
00795 start = end
00796 end += 12
00797 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00798 start = end
00799 end += 4
00800 (length,) = _struct_I.unpack(str[start:end])
00801 start = end
00802 end += length
00803 if python3:
00804 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00805 else:
00806 self.action_feedback.header.frame_id = str[start:end]
00807 _x = self
00808 start = end
00809 end += 8
00810 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00811 start = end
00812 end += 4
00813 (length,) = _struct_I.unpack(str[start:end])
00814 start = end
00815 end += length
00816 if python3:
00817 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00818 else:
00819 self.action_feedback.status.goal_id.id = str[start:end]
00820 start = end
00821 end += 1
00822 (self.action_feedback.status.status,) = _struct_B.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.text = str[start:end].decode('utf-8')
00830 else:
00831 self.action_feedback.status.text = str[start:end]
00832 return self
00833 except struct.error as e:
00834 raise genpy.DeserializationError(e)
00835
00836
00837 def serialize_numpy(self, buff, numpy):
00838 """
00839 serialize message with numpy array types into buffer
00840 :param buff: buffer, ``StringIO``
00841 :param numpy: numpy python module
00842 """
00843 try:
00844 _x = self
00845 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00846 _x = self.action_goal.header.frame_id
00847 length = len(_x)
00848 if python3 or type(_x) == unicode:
00849 _x = _x.encode('utf-8')
00850 length = len(_x)
00851 buff.write(struct.pack('<I%ss'%length, length, _x))
00852 _x = self
00853 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00854 _x = self.action_goal.goal_id.id
00855 length = len(_x)
00856 if python3 or type(_x) == unicode:
00857 _x = _x.encode('utf-8')
00858 length = len(_x)
00859 buff.write(struct.pack('<I%ss'%length, length, _x))
00860 _x = self
00861 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))
00862 _x = self.action_goal.goal.cloud.header.frame_id
00863 length = len(_x)
00864 if python3 or type(_x) == unicode:
00865 _x = _x.encode('utf-8')
00866 length = len(_x)
00867 buff.write(struct.pack('<I%ss'%length, length, _x))
00868 _x = self
00869 buff.write(_struct_2I.pack(_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width))
00870 length = len(self.action_goal.goal.cloud.fields)
00871 buff.write(_struct_I.pack(length))
00872 for val1 in self.action_goal.goal.cloud.fields:
00873 _x = val1.name
00874 length = len(_x)
00875 if python3 or type(_x) == unicode:
00876 _x = _x.encode('utf-8')
00877 length = len(_x)
00878 buff.write(struct.pack('<I%ss'%length, length, _x))
00879 _x = val1
00880 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00881 _x = self
00882 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))
00883 _x = self.action_goal.goal.cloud.data
00884 length = len(_x)
00885
00886 if type(_x) in [list, tuple]:
00887 buff.write(struct.pack('<I%sB'%length, length, *_x))
00888 else:
00889 buff.write(struct.pack('<I%ss'%length, length, _x))
00890 _x = self
00891 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))
00892 _x = self.action_goal.goal.box_pose.header.frame_id
00893 length = len(_x)
00894 if python3 or type(_x) == unicode:
00895 _x = _x.encode('utf-8')
00896 length = len(_x)
00897 buff.write(struct.pack('<I%ss'%length, length, _x))
00898 _x = self
00899 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))
00900 _x = self.action_result.header.frame_id
00901 length = len(_x)
00902 if python3 or type(_x) == unicode:
00903 _x = _x.encode('utf-8')
00904 length = len(_x)
00905 buff.write(struct.pack('<I%ss'%length, length, _x))
00906 _x = self
00907 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00908 _x = self.action_result.status.goal_id.id
00909 length = len(_x)
00910 if python3 or type(_x) == unicode:
00911 _x = _x.encode('utf-8')
00912 length = len(_x)
00913 buff.write(struct.pack('<I%ss'%length, length, _x))
00914 buff.write(_struct_B.pack(self.action_result.status.status))
00915 _x = self.action_result.status.text
00916 length = len(_x)
00917 if python3 or type(_x) == unicode:
00918 _x = _x.encode('utf-8')
00919 length = len(_x)
00920 buff.write(struct.pack('<I%ss'%length, length, _x))
00921 _x = self
00922 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))
00923 _x = self.action_result.result.box_pose.header.frame_id
00924 length = len(_x)
00925 if python3 or type(_x) == unicode:
00926 _x = _x.encode('utf-8')
00927 length = len(_x)
00928 buff.write(struct.pack('<I%ss'%length, length, _x))
00929 _x = self
00930 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))
00931 _x = self.action_result.result.contents.header.frame_id
00932 length = len(_x)
00933 if python3 or type(_x) == unicode:
00934 _x = _x.encode('utf-8')
00935 length = len(_x)
00936 buff.write(struct.pack('<I%ss'%length, length, _x))
00937 _x = self
00938 buff.write(_struct_2I.pack(_x.action_result.result.contents.height, _x.action_result.result.contents.width))
00939 length = len(self.action_result.result.contents.fields)
00940 buff.write(_struct_I.pack(length))
00941 for val1 in self.action_result.result.contents.fields:
00942 _x = val1.name
00943 length = len(_x)
00944 if python3 or type(_x) == unicode:
00945 _x = _x.encode('utf-8')
00946 length = len(_x)
00947 buff.write(struct.pack('<I%ss'%length, length, _x))
00948 _x = val1
00949 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00950 _x = self
00951 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))
00952 _x = self.action_result.result.contents.data
00953 length = len(_x)
00954
00955 if type(_x) in [list, tuple]:
00956 buff.write(struct.pack('<I%sB'%length, length, *_x))
00957 else:
00958 buff.write(struct.pack('<I%ss'%length, length, _x))
00959 _x = self
00960 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))
00961 _x = self.action_result.result.container.header.frame_id
00962 length = len(_x)
00963 if python3 or type(_x) == unicode:
00964 _x = _x.encode('utf-8')
00965 length = len(_x)
00966 buff.write(struct.pack('<I%ss'%length, length, _x))
00967 _x = self
00968 buff.write(_struct_2I.pack(_x.action_result.result.container.height, _x.action_result.result.container.width))
00969 length = len(self.action_result.result.container.fields)
00970 buff.write(_struct_I.pack(length))
00971 for val1 in self.action_result.result.container.fields:
00972 _x = val1.name
00973 length = len(_x)
00974 if python3 or type(_x) == unicode:
00975 _x = _x.encode('utf-8')
00976 length = len(_x)
00977 buff.write(struct.pack('<I%ss'%length, length, _x))
00978 _x = val1
00979 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00980 _x = self
00981 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))
00982 _x = self.action_result.result.container.data
00983 length = len(_x)
00984
00985 if type(_x) in [list, tuple]:
00986 buff.write(struct.pack('<I%sB'%length, length, *_x))
00987 else:
00988 buff.write(struct.pack('<I%ss'%length, length, _x))
00989 buff.write(_struct_B.pack(self.action_result.result.container.is_dense))
00990 length = len(self.action_result.result.clusters)
00991 buff.write(_struct_I.pack(length))
00992 for val1 in self.action_result.result.clusters:
00993 _v5 = val1.header
00994 buff.write(_struct_I.pack(_v5.seq))
00995 _v6 = _v5.stamp
00996 _x = _v6
00997 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00998 _x = _v5.frame_id
00999 length = len(_x)
01000 if python3 or type(_x) == unicode:
01001 _x = _x.encode('utf-8')
01002 length = len(_x)
01003 buff.write(struct.pack('<I%ss'%length, length, _x))
01004 _x = val1
01005 buff.write(_struct_2I.pack(_x.height, _x.width))
01006 length = len(val1.fields)
01007 buff.write(_struct_I.pack(length))
01008 for val2 in val1.fields:
01009 _x = val2.name
01010 length = len(_x)
01011 if python3 or type(_x) == unicode:
01012 _x = _x.encode('utf-8')
01013 length = len(_x)
01014 buff.write(struct.pack('<I%ss'%length, length, _x))
01015 _x = val2
01016 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01017 _x = val1
01018 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
01019 _x = val1.data
01020 length = len(_x)
01021
01022 if type(_x) in [list, tuple]:
01023 buff.write(struct.pack('<I%sB'%length, length, *_x))
01024 else:
01025 buff.write(struct.pack('<I%ss'%length, length, _x))
01026 buff.write(_struct_B.pack(val1.is_dense))
01027 _x = self
01028 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
01029 _x = self.action_feedback.header.frame_id
01030 length = len(_x)
01031 if python3 or type(_x) == unicode:
01032 _x = _x.encode('utf-8')
01033 length = len(_x)
01034 buff.write(struct.pack('<I%ss'%length, length, _x))
01035 _x = self
01036 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
01037 _x = self.action_feedback.status.goal_id.id
01038 length = len(_x)
01039 if python3 or type(_x) == unicode:
01040 _x = _x.encode('utf-8')
01041 length = len(_x)
01042 buff.write(struct.pack('<I%ss'%length, length, _x))
01043 buff.write(_struct_B.pack(self.action_feedback.status.status))
01044 _x = self.action_feedback.status.text
01045 length = len(_x)
01046 if python3 or type(_x) == unicode:
01047 _x = _x.encode('utf-8')
01048 length = len(_x)
01049 buff.write(struct.pack('<I%ss'%length, length, _x))
01050 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
01051 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
01052
01053 def deserialize_numpy(self, str, numpy):
01054 """
01055 unpack serialized message in str into this message instance using numpy for array types
01056 :param str: byte array of serialized message, ``str``
01057 :param numpy: numpy python module
01058 """
01059 try:
01060 if self.action_goal is None:
01061 self.action_goal = object_manipulation_msgs.msg.FindContainerActionGoal()
01062 if self.action_result is None:
01063 self.action_result = object_manipulation_msgs.msg.FindContainerActionResult()
01064 if self.action_feedback is None:
01065 self.action_feedback = object_manipulation_msgs.msg.FindContainerActionFeedback()
01066 end = 0
01067 _x = self
01068 start = end
01069 end += 12
01070 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01071 start = end
01072 end += 4
01073 (length,) = _struct_I.unpack(str[start:end])
01074 start = end
01075 end += length
01076 if python3:
01077 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
01078 else:
01079 self.action_goal.header.frame_id = str[start:end]
01080 _x = self
01081 start = end
01082 end += 8
01083 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01084 start = end
01085 end += 4
01086 (length,) = _struct_I.unpack(str[start:end])
01087 start = end
01088 end += length
01089 if python3:
01090 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
01091 else:
01092 self.action_goal.goal_id.id = str[start:end]
01093 _x = self
01094 start = end
01095 end += 12
01096 (_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])
01097 start = end
01098 end += 4
01099 (length,) = _struct_I.unpack(str[start:end])
01100 start = end
01101 end += length
01102 if python3:
01103 self.action_goal.goal.cloud.header.frame_id = str[start:end].decode('utf-8')
01104 else:
01105 self.action_goal.goal.cloud.header.frame_id = str[start:end]
01106 _x = self
01107 start = end
01108 end += 8
01109 (_x.action_goal.goal.cloud.height, _x.action_goal.goal.cloud.width,) = _struct_2I.unpack(str[start:end])
01110 start = end
01111 end += 4
01112 (length,) = _struct_I.unpack(str[start:end])
01113 self.action_goal.goal.cloud.fields = []
01114 for i in range(0, length):
01115 val1 = sensor_msgs.msg.PointField()
01116 start = end
01117 end += 4
01118 (length,) = _struct_I.unpack(str[start:end])
01119 start = end
01120 end += length
01121 if python3:
01122 val1.name = str[start:end].decode('utf-8')
01123 else:
01124 val1.name = str[start:end]
01125 _x = val1
01126 start = end
01127 end += 9
01128 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01129 self.action_goal.goal.cloud.fields.append(val1)
01130 _x = self
01131 start = end
01132 end += 9
01133 (_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])
01134 self.action_goal.goal.cloud.is_bigendian = bool(self.action_goal.goal.cloud.is_bigendian)
01135 start = end
01136 end += 4
01137 (length,) = _struct_I.unpack(str[start:end])
01138 start = end
01139 end += length
01140 self.action_goal.goal.cloud.data = str[start:end]
01141 _x = self
01142 start = end
01143 end += 13
01144 (_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])
01145 self.action_goal.goal.cloud.is_dense = bool(self.action_goal.goal.cloud.is_dense)
01146 start = end
01147 end += 4
01148 (length,) = _struct_I.unpack(str[start:end])
01149 start = end
01150 end += length
01151 if python3:
01152 self.action_goal.goal.box_pose.header.frame_id = str[start:end].decode('utf-8')
01153 else:
01154 self.action_goal.goal.box_pose.header.frame_id = str[start:end]
01155 _x = self
01156 start = end
01157 end += 116
01158 (_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])
01159 start = end
01160 end += 4
01161 (length,) = _struct_I.unpack(str[start:end])
01162 start = end
01163 end += length
01164 if python3:
01165 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01166 else:
01167 self.action_result.header.frame_id = str[start:end]
01168 _x = self
01169 start = end
01170 end += 8
01171 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01172 start = end
01173 end += 4
01174 (length,) = _struct_I.unpack(str[start:end])
01175 start = end
01176 end += length
01177 if python3:
01178 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01179 else:
01180 self.action_result.status.goal_id.id = str[start:end]
01181 start = end
01182 end += 1
01183 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01184 start = end
01185 end += 4
01186 (length,) = _struct_I.unpack(str[start:end])
01187 start = end
01188 end += length
01189 if python3:
01190 self.action_result.status.text = str[start:end].decode('utf-8')
01191 else:
01192 self.action_result.status.text = str[start:end]
01193 _x = self
01194 start = end
01195 end += 12
01196 (_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])
01197 start = end
01198 end += 4
01199 (length,) = _struct_I.unpack(str[start:end])
01200 start = end
01201 end += length
01202 if python3:
01203 self.action_result.result.box_pose.header.frame_id = str[start:end].decode('utf-8')
01204 else:
01205 self.action_result.result.box_pose.header.frame_id = str[start:end]
01206 _x = self
01207 start = end
01208 end += 92
01209 (_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])
01210 start = end
01211 end += 4
01212 (length,) = _struct_I.unpack(str[start:end])
01213 start = end
01214 end += length
01215 if python3:
01216 self.action_result.result.contents.header.frame_id = str[start:end].decode('utf-8')
01217 else:
01218 self.action_result.result.contents.header.frame_id = str[start:end]
01219 _x = self
01220 start = end
01221 end += 8
01222 (_x.action_result.result.contents.height, _x.action_result.result.contents.width,) = _struct_2I.unpack(str[start:end])
01223 start = end
01224 end += 4
01225 (length,) = _struct_I.unpack(str[start:end])
01226 self.action_result.result.contents.fields = []
01227 for i in range(0, length):
01228 val1 = sensor_msgs.msg.PointField()
01229 start = end
01230 end += 4
01231 (length,) = _struct_I.unpack(str[start:end])
01232 start = end
01233 end += length
01234 if python3:
01235 val1.name = str[start:end].decode('utf-8')
01236 else:
01237 val1.name = str[start:end]
01238 _x = val1
01239 start = end
01240 end += 9
01241 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01242 self.action_result.result.contents.fields.append(val1)
01243 _x = self
01244 start = end
01245 end += 9
01246 (_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])
01247 self.action_result.result.contents.is_bigendian = bool(self.action_result.result.contents.is_bigendian)
01248 start = end
01249 end += 4
01250 (length,) = _struct_I.unpack(str[start:end])
01251 start = end
01252 end += length
01253 self.action_result.result.contents.data = str[start:end]
01254 _x = self
01255 start = end
01256 end += 13
01257 (_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])
01258 self.action_result.result.contents.is_dense = bool(self.action_result.result.contents.is_dense)
01259 start = end
01260 end += 4
01261 (length,) = _struct_I.unpack(str[start:end])
01262 start = end
01263 end += length
01264 if python3:
01265 self.action_result.result.container.header.frame_id = str[start:end].decode('utf-8')
01266 else:
01267 self.action_result.result.container.header.frame_id = str[start:end]
01268 _x = self
01269 start = end
01270 end += 8
01271 (_x.action_result.result.container.height, _x.action_result.result.container.width,) = _struct_2I.unpack(str[start:end])
01272 start = end
01273 end += 4
01274 (length,) = _struct_I.unpack(str[start:end])
01275 self.action_result.result.container.fields = []
01276 for i in range(0, length):
01277 val1 = sensor_msgs.msg.PointField()
01278 start = end
01279 end += 4
01280 (length,) = _struct_I.unpack(str[start:end])
01281 start = end
01282 end += length
01283 if python3:
01284 val1.name = str[start:end].decode('utf-8')
01285 else:
01286 val1.name = str[start:end]
01287 _x = val1
01288 start = end
01289 end += 9
01290 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01291 self.action_result.result.container.fields.append(val1)
01292 _x = self
01293 start = end
01294 end += 9
01295 (_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])
01296 self.action_result.result.container.is_bigendian = bool(self.action_result.result.container.is_bigendian)
01297 start = end
01298 end += 4
01299 (length,) = _struct_I.unpack(str[start:end])
01300 start = end
01301 end += length
01302 self.action_result.result.container.data = str[start:end]
01303 start = end
01304 end += 1
01305 (self.action_result.result.container.is_dense,) = _struct_B.unpack(str[start:end])
01306 self.action_result.result.container.is_dense = bool(self.action_result.result.container.is_dense)
01307 start = end
01308 end += 4
01309 (length,) = _struct_I.unpack(str[start:end])
01310 self.action_result.result.clusters = []
01311 for i in range(0, length):
01312 val1 = sensor_msgs.msg.PointCloud2()
01313 _v7 = val1.header
01314 start = end
01315 end += 4
01316 (_v7.seq,) = _struct_I.unpack(str[start:end])
01317 _v8 = _v7.stamp
01318 _x = _v8
01319 start = end
01320 end += 8
01321 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01322 start = end
01323 end += 4
01324 (length,) = _struct_I.unpack(str[start:end])
01325 start = end
01326 end += length
01327 if python3:
01328 _v7.frame_id = str[start:end].decode('utf-8')
01329 else:
01330 _v7.frame_id = str[start:end]
01331 _x = val1
01332 start = end
01333 end += 8
01334 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01335 start = end
01336 end += 4
01337 (length,) = _struct_I.unpack(str[start:end])
01338 val1.fields = []
01339 for i in range(0, length):
01340 val2 = sensor_msgs.msg.PointField()
01341 start = end
01342 end += 4
01343 (length,) = _struct_I.unpack(str[start:end])
01344 start = end
01345 end += length
01346 if python3:
01347 val2.name = str[start:end].decode('utf-8')
01348 else:
01349 val2.name = str[start:end]
01350 _x = val2
01351 start = end
01352 end += 9
01353 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01354 val1.fields.append(val2)
01355 _x = val1
01356 start = end
01357 end += 9
01358 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
01359 val1.is_bigendian = bool(val1.is_bigendian)
01360 start = end
01361 end += 4
01362 (length,) = _struct_I.unpack(str[start:end])
01363 start = end
01364 end += length
01365 val1.data = str[start:end]
01366 start = end
01367 end += 1
01368 (val1.is_dense,) = _struct_B.unpack(str[start:end])
01369 val1.is_dense = bool(val1.is_dense)
01370 self.action_result.result.clusters.append(val1)
01371 _x = self
01372 start = end
01373 end += 12
01374 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01375 start = end
01376 end += 4
01377 (length,) = _struct_I.unpack(str[start:end])
01378 start = end
01379 end += length
01380 if python3:
01381 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01382 else:
01383 self.action_feedback.header.frame_id = str[start:end]
01384 _x = self
01385 start = end
01386 end += 8
01387 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01388 start = end
01389 end += 4
01390 (length,) = _struct_I.unpack(str[start:end])
01391 start = end
01392 end += length
01393 if python3:
01394 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01395 else:
01396 self.action_feedback.status.goal_id.id = str[start:end]
01397 start = end
01398 end += 1
01399 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01400 start = end
01401 end += 4
01402 (length,) = _struct_I.unpack(str[start:end])
01403 start = end
01404 end += length
01405 if python3:
01406 self.action_feedback.status.text = str[start:end].decode('utf-8')
01407 else:
01408 self.action_feedback.status.text = str[start:end]
01409 return self
01410 except struct.error as e:
01411 raise genpy.DeserializationError(e)
01412
01413 _struct_I = genpy.struct_I
01414 _struct_IBI = struct.Struct("<IBI")
01415 _struct_B = struct.Struct("<B")
01416 _struct_10d3I = struct.Struct("<10d3I")
01417 _struct_13d3I = struct.Struct("<13d3I")
01418 _struct_3I = struct.Struct("<3I")
01419 _struct_B3I = struct.Struct("<B3I")
01420 _struct_B2I = struct.Struct("<B2I")
01421 _struct_2I = struct.Struct("<2I")