00001 """autogenerated by genpy from object_segmentation_gui/ObjectSegmentationGuiActionResult.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 arm_navigation_msgs.msg
00008 import tabletop_object_detector.msg
00009 import actionlib_msgs.msg
00010 import geometry_msgs.msg
00011 import sensor_msgs.msg
00012 import genpy
00013 import object_segmentation_gui.msg
00014 import std_msgs.msg
00015
00016 class ObjectSegmentationGuiActionResult(genpy.Message):
00017 _md5sum = "862ad847b21c3b6991ff08c9f9bd5b66"
00018 _type = "object_segmentation_gui/ObjectSegmentationGuiActionResult"
00019 _has_header = True
00020 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00021
00022 Header header
00023 actionlib_msgs/GoalStatus status
00024 ObjectSegmentationGuiResult result
00025
00026 ================================================================================
00027 MSG: std_msgs/Header
00028 # Standard metadata for higher-level stamped data types.
00029 # This is generally used to communicate timestamped data
00030 # in a particular coordinate frame.
00031 #
00032 # sequence ID: consecutively increasing ID
00033 uint32 seq
00034 #Two-integer timestamp that is expressed as:
00035 # * stamp.secs: seconds (stamp_secs) since epoch
00036 # * stamp.nsecs: nanoseconds since stamp_secs
00037 # time-handling sugar is provided by the client library
00038 time stamp
00039 #Frame this data is associated with
00040 # 0: no frame
00041 # 1: global frame
00042 string frame_id
00043
00044 ================================================================================
00045 MSG: actionlib_msgs/GoalStatus
00046 GoalID goal_id
00047 uint8 status
00048 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00049 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00050 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00051 # and has since completed its execution (Terminal State)
00052 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00053 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00054 # to some failure (Terminal State)
00055 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00056 # because the goal was unattainable or invalid (Terminal State)
00057 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00058 # and has not yet completed execution
00059 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00060 # but the action server has not yet confirmed that the goal is canceled
00061 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00062 # and was successfully cancelled (Terminal State)
00063 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00064 # sent over the wire by an action server
00065
00066 #Allow for the user to associate a string with GoalStatus for debugging
00067 string text
00068
00069
00070 ================================================================================
00071 MSG: actionlib_msgs/GoalID
00072 # The stamp should store the time at which this goal was requested.
00073 # It is used by an action server when it tries to preempt all
00074 # goals that were requested before a certain time
00075 time stamp
00076
00077 # The id provides a way to associate feedback and
00078 # result message with specific goal requests. The id
00079 # specified must be unique.
00080 string id
00081
00082
00083 ================================================================================
00084 MSG: object_segmentation_gui/ObjectSegmentationGuiResult
00085 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00086 # The information for the plane that has been detected
00087 tabletop_object_detector/Table table
00088
00089 # The raw clusters detected in the scan
00090 sensor_msgs/PointCloud[] clusters
00091
00092 # Whether the detection has succeeded or failed
00093 int32 NO_CLOUD_RECEIVED = 1
00094 int32 NO_TABLE = 2
00095 int32 OTHER_ERROR = 3
00096 int32 SUCCESS = 4
00097 int32 result
00098
00099
00100 ================================================================================
00101 MSG: tabletop_object_detector/Table
00102 # Informs that a planar table has been detected at a given location
00103
00104 # The pose gives you the transform that take you to the coordinate system
00105 # of the table, with the origin somewhere in the table plane and the
00106 # z axis normal to the plane
00107 geometry_msgs/PoseStamped pose
00108
00109 # These values give you the observed extents of the table, along x and y,
00110 # in the table's own coordinate system (above)
00111 # there is no guarantee that the origin of the table coordinate system is
00112 # inside the boundary defined by these values.
00113 float32 x_min
00114 float32 x_max
00115 float32 y_min
00116 float32 y_max
00117
00118 # There is no guarantee that the table does NOT extend further than these
00119 # values; this is just as far as we've observed it.
00120
00121
00122 # Newer table definition as triangle mesh of convex hull (relative to pose)
00123 arm_navigation_msgs/Shape convex_hull
00124
00125 ================================================================================
00126 MSG: geometry_msgs/PoseStamped
00127 # A Pose with reference coordinate frame and timestamp
00128 Header header
00129 Pose pose
00130
00131 ================================================================================
00132 MSG: geometry_msgs/Pose
00133 # A representation of pose in free space, composed of postion and orientation.
00134 Point position
00135 Quaternion orientation
00136
00137 ================================================================================
00138 MSG: geometry_msgs/Point
00139 # This contains the position of a point in free space
00140 float64 x
00141 float64 y
00142 float64 z
00143
00144 ================================================================================
00145 MSG: geometry_msgs/Quaternion
00146 # This represents an orientation in free space in quaternion form.
00147
00148 float64 x
00149 float64 y
00150 float64 z
00151 float64 w
00152
00153 ================================================================================
00154 MSG: arm_navigation_msgs/Shape
00155 byte SPHERE=0
00156 byte BOX=1
00157 byte CYLINDER=2
00158 byte MESH=3
00159
00160 byte type
00161
00162
00163 #### define sphere, box, cylinder ####
00164 # the origin of each shape is considered at the shape's center
00165
00166 # for sphere
00167 # radius := dimensions[0]
00168
00169 # for cylinder
00170 # radius := dimensions[0]
00171 # length := dimensions[1]
00172 # the length is along the Z axis
00173
00174 # for box
00175 # size_x := dimensions[0]
00176 # size_y := dimensions[1]
00177 # size_z := dimensions[2]
00178 float64[] dimensions
00179
00180
00181 #### define mesh ####
00182
00183 # list of triangles; triangle k is defined by tre vertices located
00184 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00185 int32[] triangles
00186 geometry_msgs/Point[] vertices
00187
00188 ================================================================================
00189 MSG: sensor_msgs/PointCloud
00190 # This message holds a collection of 3d points, plus optional additional
00191 # information about each point.
00192
00193 # Time of sensor data acquisition, coordinate frame ID.
00194 Header header
00195
00196 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00197 # in the frame given in the header.
00198 geometry_msgs/Point32[] points
00199
00200 # Each channel should have the same number of elements as points array,
00201 # and the data in each channel should correspond 1:1 with each point.
00202 # Channel names in common practice are listed in ChannelFloat32.msg.
00203 ChannelFloat32[] channels
00204
00205 ================================================================================
00206 MSG: geometry_msgs/Point32
00207 # This contains the position of a point in free space(with 32 bits of precision).
00208 # It is recommeded to use Point wherever possible instead of Point32.
00209 #
00210 # This recommendation is to promote interoperability.
00211 #
00212 # This message is designed to take up less space when sending
00213 # lots of points at once, as in the case of a PointCloud.
00214
00215 float32 x
00216 float32 y
00217 float32 z
00218 ================================================================================
00219 MSG: sensor_msgs/ChannelFloat32
00220 # This message is used by the PointCloud message to hold optional data
00221 # associated with each point in the cloud. The length of the values
00222 # array should be the same as the length of the points array in the
00223 # PointCloud, and each value should be associated with the corresponding
00224 # point.
00225
00226 # Channel names in existing practice include:
00227 # "u", "v" - row and column (respectively) in the left stereo image.
00228 # This is opposite to usual conventions but remains for
00229 # historical reasons. The newer PointCloud2 message has no
00230 # such problem.
00231 # "rgb" - For point clouds produced by color stereo cameras. uint8
00232 # (R,G,B) values packed into the least significant 24 bits,
00233 # in order.
00234 # "intensity" - laser or pixel intensity.
00235 # "distance"
00236
00237 # The channel name should give semantics of the channel (e.g.
00238 # "intensity" instead of "value").
00239 string name
00240
00241 # The values array should be 1-1 with the elements of the associated
00242 # PointCloud.
00243 float32[] values
00244
00245 """
00246 __slots__ = ['header','status','result']
00247 _slot_types = ['std_msgs/Header','actionlib_msgs/GoalStatus','object_segmentation_gui/ObjectSegmentationGuiResult']
00248
00249 def __init__(self, *args, **kwds):
00250 """
00251 Constructor. Any message fields that are implicitly/explicitly
00252 set to None will be assigned a default value. The recommend
00253 use is keyword arguments as this is more robust to future message
00254 changes. You cannot mix in-order arguments and keyword arguments.
00255
00256 The available fields are:
00257 header,status,result
00258
00259 :param args: complete set of field values, in .msg order
00260 :param kwds: use keyword arguments corresponding to message field names
00261 to set specific fields.
00262 """
00263 if args or kwds:
00264 super(ObjectSegmentationGuiActionResult, self).__init__(*args, **kwds)
00265 #message fields cannot be None, assign default values for those that are
00266 if self.header is None:
00267 self.header = std_msgs.msg.Header()
00268 if self.status is None:
00269 self.status = actionlib_msgs.msg.GoalStatus()
00270 if self.result is None:
00271 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00272 else:
00273 self.header = std_msgs.msg.Header()
00274 self.status = actionlib_msgs.msg.GoalStatus()
00275 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00276
00277 def _get_types(self):
00278 """
00279 internal API method
00280 """
00281 return self._slot_types
00282
00283 def serialize(self, buff):
00284 """
00285 serialize message into buffer
00286 :param buff: buffer, ``StringIO``
00287 """
00288 try:
00289 _x = self
00290 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00291 _x = self.header.frame_id
00292 length = len(_x)
00293 if python3 or type(_x) == unicode:
00294 _x = _x.encode('utf-8')
00295 length = len(_x)
00296 buff.write(struct.pack('<I%ss'%length, length, _x))
00297 _x = self
00298 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00299 _x = self.status.goal_id.id
00300 length = len(_x)
00301 if python3 or type(_x) == unicode:
00302 _x = _x.encode('utf-8')
00303 length = len(_x)
00304 buff.write(struct.pack('<I%ss'%length, length, _x))
00305 buff.write(_struct_B.pack(self.status.status))
00306 _x = self.status.text
00307 length = len(_x)
00308 if python3 or type(_x) == unicode:
00309 _x = _x.encode('utf-8')
00310 length = len(_x)
00311 buff.write(struct.pack('<I%ss'%length, length, _x))
00312 _x = self
00313 buff.write(_struct_3I.pack(_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs))
00314 _x = self.result.table.pose.header.frame_id
00315 length = len(_x)
00316 if python3 or type(_x) == unicode:
00317 _x = _x.encode('utf-8')
00318 length = len(_x)
00319 buff.write(struct.pack('<I%ss'%length, length, _x))
00320 _x = self
00321 buff.write(_struct_7d4fb.pack(_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max, _x.result.table.convex_hull.type))
00322 length = len(self.result.table.convex_hull.dimensions)
00323 buff.write(_struct_I.pack(length))
00324 pattern = '<%sd'%length
00325 buff.write(struct.pack(pattern, *self.result.table.convex_hull.dimensions))
00326 length = len(self.result.table.convex_hull.triangles)
00327 buff.write(_struct_I.pack(length))
00328 pattern = '<%si'%length
00329 buff.write(struct.pack(pattern, *self.result.table.convex_hull.triangles))
00330 length = len(self.result.table.convex_hull.vertices)
00331 buff.write(_struct_I.pack(length))
00332 for val1 in self.result.table.convex_hull.vertices:
00333 _x = val1
00334 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00335 length = len(self.result.clusters)
00336 buff.write(_struct_I.pack(length))
00337 for val1 in self.result.clusters:
00338 _v1 = val1.header
00339 buff.write(_struct_I.pack(_v1.seq))
00340 _v2 = _v1.stamp
00341 _x = _v2
00342 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00343 _x = _v1.frame_id
00344 length = len(_x)
00345 if python3 or type(_x) == unicode:
00346 _x = _x.encode('utf-8')
00347 length = len(_x)
00348 buff.write(struct.pack('<I%ss'%length, length, _x))
00349 length = len(val1.points)
00350 buff.write(_struct_I.pack(length))
00351 for val2 in val1.points:
00352 _x = val2
00353 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00354 length = len(val1.channels)
00355 buff.write(_struct_I.pack(length))
00356 for val2 in val1.channels:
00357 _x = val2.name
00358 length = len(_x)
00359 if python3 or type(_x) == unicode:
00360 _x = _x.encode('utf-8')
00361 length = len(_x)
00362 buff.write(struct.pack('<I%ss'%length, length, _x))
00363 length = len(val2.values)
00364 buff.write(_struct_I.pack(length))
00365 pattern = '<%sf'%length
00366 buff.write(struct.pack(pattern, *val2.values))
00367 buff.write(_struct_i.pack(self.result.result))
00368 except struct.error as se: self._check_types(se)
00369 except TypeError as te: self._check_types(te)
00370
00371 def deserialize(self, str):
00372 """
00373 unpack serialized message in str into this message instance
00374 :param str: byte array of serialized message, ``str``
00375 """
00376 try:
00377 if self.header is None:
00378 self.header = std_msgs.msg.Header()
00379 if self.status is None:
00380 self.status = actionlib_msgs.msg.GoalStatus()
00381 if self.result is None:
00382 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00383 end = 0
00384 _x = self
00385 start = end
00386 end += 12
00387 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00388 start = end
00389 end += 4
00390 (length,) = _struct_I.unpack(str[start:end])
00391 start = end
00392 end += length
00393 if python3:
00394 self.header.frame_id = str[start:end].decode('utf-8')
00395 else:
00396 self.header.frame_id = str[start:end]
00397 _x = self
00398 start = end
00399 end += 8
00400 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00401 start = end
00402 end += 4
00403 (length,) = _struct_I.unpack(str[start:end])
00404 start = end
00405 end += length
00406 if python3:
00407 self.status.goal_id.id = str[start:end].decode('utf-8')
00408 else:
00409 self.status.goal_id.id = str[start:end]
00410 start = end
00411 end += 1
00412 (self.status.status,) = _struct_B.unpack(str[start:end])
00413 start = end
00414 end += 4
00415 (length,) = _struct_I.unpack(str[start:end])
00416 start = end
00417 end += length
00418 if python3:
00419 self.status.text = str[start:end].decode('utf-8')
00420 else:
00421 self.status.text = str[start:end]
00422 _x = self
00423 start = end
00424 end += 12
00425 (_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00426 start = end
00427 end += 4
00428 (length,) = _struct_I.unpack(str[start:end])
00429 start = end
00430 end += length
00431 if python3:
00432 self.result.table.pose.header.frame_id = str[start:end].decode('utf-8')
00433 else:
00434 self.result.table.pose.header.frame_id = str[start:end]
00435 _x = self
00436 start = end
00437 end += 73
00438 (_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max, _x.result.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
00439 start = end
00440 end += 4
00441 (length,) = _struct_I.unpack(str[start:end])
00442 pattern = '<%sd'%length
00443 start = end
00444 end += struct.calcsize(pattern)
00445 self.result.table.convex_hull.dimensions = struct.unpack(pattern, str[start:end])
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 pattern = '<%si'%length
00450 start = end
00451 end += struct.calcsize(pattern)
00452 self.result.table.convex_hull.triangles = struct.unpack(pattern, str[start:end])
00453 start = end
00454 end += 4
00455 (length,) = _struct_I.unpack(str[start:end])
00456 self.result.table.convex_hull.vertices = []
00457 for i in range(0, length):
00458 val1 = geometry_msgs.msg.Point()
00459 _x = val1
00460 start = end
00461 end += 24
00462 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00463 self.result.table.convex_hull.vertices.append(val1)
00464 start = end
00465 end += 4
00466 (length,) = _struct_I.unpack(str[start:end])
00467 self.result.clusters = []
00468 for i in range(0, length):
00469 val1 = sensor_msgs.msg.PointCloud()
00470 _v3 = val1.header
00471 start = end
00472 end += 4
00473 (_v3.seq,) = _struct_I.unpack(str[start:end])
00474 _v4 = _v3.stamp
00475 _x = _v4
00476 start = end
00477 end += 8
00478 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00479 start = end
00480 end += 4
00481 (length,) = _struct_I.unpack(str[start:end])
00482 start = end
00483 end += length
00484 if python3:
00485 _v3.frame_id = str[start:end].decode('utf-8')
00486 else:
00487 _v3.frame_id = str[start:end]
00488 start = end
00489 end += 4
00490 (length,) = _struct_I.unpack(str[start:end])
00491 val1.points = []
00492 for i in range(0, length):
00493 val2 = geometry_msgs.msg.Point32()
00494 _x = val2
00495 start = end
00496 end += 12
00497 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00498 val1.points.append(val2)
00499 start = end
00500 end += 4
00501 (length,) = _struct_I.unpack(str[start:end])
00502 val1.channels = []
00503 for i in range(0, length):
00504 val2 = sensor_msgs.msg.ChannelFloat32()
00505 start = end
00506 end += 4
00507 (length,) = _struct_I.unpack(str[start:end])
00508 start = end
00509 end += length
00510 if python3:
00511 val2.name = str[start:end].decode('utf-8')
00512 else:
00513 val2.name = str[start:end]
00514 start = end
00515 end += 4
00516 (length,) = _struct_I.unpack(str[start:end])
00517 pattern = '<%sf'%length
00518 start = end
00519 end += struct.calcsize(pattern)
00520 val2.values = struct.unpack(pattern, str[start:end])
00521 val1.channels.append(val2)
00522 self.result.clusters.append(val1)
00523 start = end
00524 end += 4
00525 (self.result.result,) = _struct_i.unpack(str[start:end])
00526 return self
00527 except struct.error as e:
00528 raise genpy.DeserializationError(e) #most likely buffer underfill
00529
00530
00531 def serialize_numpy(self, buff, numpy):
00532 """
00533 serialize message with numpy array types into buffer
00534 :param buff: buffer, ``StringIO``
00535 :param numpy: numpy python module
00536 """
00537 try:
00538 _x = self
00539 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00540 _x = self.header.frame_id
00541 length = len(_x)
00542 if python3 or type(_x) == unicode:
00543 _x = _x.encode('utf-8')
00544 length = len(_x)
00545 buff.write(struct.pack('<I%ss'%length, length, _x))
00546 _x = self
00547 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00548 _x = self.status.goal_id.id
00549 length = len(_x)
00550 if python3 or type(_x) == unicode:
00551 _x = _x.encode('utf-8')
00552 length = len(_x)
00553 buff.write(struct.pack('<I%ss'%length, length, _x))
00554 buff.write(_struct_B.pack(self.status.status))
00555 _x = self.status.text
00556 length = len(_x)
00557 if python3 or type(_x) == unicode:
00558 _x = _x.encode('utf-8')
00559 length = len(_x)
00560 buff.write(struct.pack('<I%ss'%length, length, _x))
00561 _x = self
00562 buff.write(_struct_3I.pack(_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs))
00563 _x = self.result.table.pose.header.frame_id
00564 length = len(_x)
00565 if python3 or type(_x) == unicode:
00566 _x = _x.encode('utf-8')
00567 length = len(_x)
00568 buff.write(struct.pack('<I%ss'%length, length, _x))
00569 _x = self
00570 buff.write(_struct_7d4fb.pack(_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max, _x.result.table.convex_hull.type))
00571 length = len(self.result.table.convex_hull.dimensions)
00572 buff.write(_struct_I.pack(length))
00573 pattern = '<%sd'%length
00574 buff.write(self.result.table.convex_hull.dimensions.tostring())
00575 length = len(self.result.table.convex_hull.triangles)
00576 buff.write(_struct_I.pack(length))
00577 pattern = '<%si'%length
00578 buff.write(self.result.table.convex_hull.triangles.tostring())
00579 length = len(self.result.table.convex_hull.vertices)
00580 buff.write(_struct_I.pack(length))
00581 for val1 in self.result.table.convex_hull.vertices:
00582 _x = val1
00583 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00584 length = len(self.result.clusters)
00585 buff.write(_struct_I.pack(length))
00586 for val1 in self.result.clusters:
00587 _v5 = val1.header
00588 buff.write(_struct_I.pack(_v5.seq))
00589 _v6 = _v5.stamp
00590 _x = _v6
00591 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00592 _x = _v5.frame_id
00593 length = len(_x)
00594 if python3 or type(_x) == unicode:
00595 _x = _x.encode('utf-8')
00596 length = len(_x)
00597 buff.write(struct.pack('<I%ss'%length, length, _x))
00598 length = len(val1.points)
00599 buff.write(_struct_I.pack(length))
00600 for val2 in val1.points:
00601 _x = val2
00602 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00603 length = len(val1.channels)
00604 buff.write(_struct_I.pack(length))
00605 for val2 in val1.channels:
00606 _x = val2.name
00607 length = len(_x)
00608 if python3 or type(_x) == unicode:
00609 _x = _x.encode('utf-8')
00610 length = len(_x)
00611 buff.write(struct.pack('<I%ss'%length, length, _x))
00612 length = len(val2.values)
00613 buff.write(_struct_I.pack(length))
00614 pattern = '<%sf'%length
00615 buff.write(val2.values.tostring())
00616 buff.write(_struct_i.pack(self.result.result))
00617 except struct.error as se: self._check_types(se)
00618 except TypeError as te: self._check_types(te)
00619
00620 def deserialize_numpy(self, str, numpy):
00621 """
00622 unpack serialized message in str into this message instance using numpy for array types
00623 :param str: byte array of serialized message, ``str``
00624 :param numpy: numpy python module
00625 """
00626 try:
00627 if self.header is None:
00628 self.header = std_msgs.msg.Header()
00629 if self.status is None:
00630 self.status = actionlib_msgs.msg.GoalStatus()
00631 if self.result is None:
00632 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00633 end = 0
00634 _x = self
00635 start = end
00636 end += 12
00637 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00638 start = end
00639 end += 4
00640 (length,) = _struct_I.unpack(str[start:end])
00641 start = end
00642 end += length
00643 if python3:
00644 self.header.frame_id = str[start:end].decode('utf-8')
00645 else:
00646 self.header.frame_id = str[start:end]
00647 _x = self
00648 start = end
00649 end += 8
00650 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00651 start = end
00652 end += 4
00653 (length,) = _struct_I.unpack(str[start:end])
00654 start = end
00655 end += length
00656 if python3:
00657 self.status.goal_id.id = str[start:end].decode('utf-8')
00658 else:
00659 self.status.goal_id.id = str[start:end]
00660 start = end
00661 end += 1
00662 (self.status.status,) = _struct_B.unpack(str[start:end])
00663 start = end
00664 end += 4
00665 (length,) = _struct_I.unpack(str[start:end])
00666 start = end
00667 end += length
00668 if python3:
00669 self.status.text = str[start:end].decode('utf-8')
00670 else:
00671 self.status.text = str[start:end]
00672 _x = self
00673 start = end
00674 end += 12
00675 (_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00676 start = end
00677 end += 4
00678 (length,) = _struct_I.unpack(str[start:end])
00679 start = end
00680 end += length
00681 if python3:
00682 self.result.table.pose.header.frame_id = str[start:end].decode('utf-8')
00683 else:
00684 self.result.table.pose.header.frame_id = str[start:end]
00685 _x = self
00686 start = end
00687 end += 73
00688 (_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max, _x.result.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
00689 start = end
00690 end += 4
00691 (length,) = _struct_I.unpack(str[start:end])
00692 pattern = '<%sd'%length
00693 start = end
00694 end += struct.calcsize(pattern)
00695 self.result.table.convex_hull.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00696 start = end
00697 end += 4
00698 (length,) = _struct_I.unpack(str[start:end])
00699 pattern = '<%si'%length
00700 start = end
00701 end += struct.calcsize(pattern)
00702 self.result.table.convex_hull.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00703 start = end
00704 end += 4
00705 (length,) = _struct_I.unpack(str[start:end])
00706 self.result.table.convex_hull.vertices = []
00707 for i in range(0, length):
00708 val1 = geometry_msgs.msg.Point()
00709 _x = val1
00710 start = end
00711 end += 24
00712 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00713 self.result.table.convex_hull.vertices.append(val1)
00714 start = end
00715 end += 4
00716 (length,) = _struct_I.unpack(str[start:end])
00717 self.result.clusters = []
00718 for i in range(0, length):
00719 val1 = sensor_msgs.msg.PointCloud()
00720 _v7 = val1.header
00721 start = end
00722 end += 4
00723 (_v7.seq,) = _struct_I.unpack(str[start:end])
00724 _v8 = _v7.stamp
00725 _x = _v8
00726 start = end
00727 end += 8
00728 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00729 start = end
00730 end += 4
00731 (length,) = _struct_I.unpack(str[start:end])
00732 start = end
00733 end += length
00734 if python3:
00735 _v7.frame_id = str[start:end].decode('utf-8')
00736 else:
00737 _v7.frame_id = str[start:end]
00738 start = end
00739 end += 4
00740 (length,) = _struct_I.unpack(str[start:end])
00741 val1.points = []
00742 for i in range(0, length):
00743 val2 = geometry_msgs.msg.Point32()
00744 _x = val2
00745 start = end
00746 end += 12
00747 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00748 val1.points.append(val2)
00749 start = end
00750 end += 4
00751 (length,) = _struct_I.unpack(str[start:end])
00752 val1.channels = []
00753 for i in range(0, length):
00754 val2 = sensor_msgs.msg.ChannelFloat32()
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 start = end
00759 end += length
00760 if python3:
00761 val2.name = str[start:end].decode('utf-8')
00762 else:
00763 val2.name = str[start:end]
00764 start = end
00765 end += 4
00766 (length,) = _struct_I.unpack(str[start:end])
00767 pattern = '<%sf'%length
00768 start = end
00769 end += struct.calcsize(pattern)
00770 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00771 val1.channels.append(val2)
00772 self.result.clusters.append(val1)
00773 start = end
00774 end += 4
00775 (self.result.result,) = _struct_i.unpack(str[start:end])
00776 return self
00777 except struct.error as e:
00778 raise genpy.DeserializationError(e) #most likely buffer underfill
00779
00780 _struct_I = genpy.struct_I
00781 _struct_B = struct.Struct("<B")
00782 _struct_7d4fb = struct.Struct("<7d4fb")
00783 _struct_3f = struct.Struct("<3f")
00784 _struct_i = struct.Struct("<i")
00785 _struct_3I = struct.Struct("<3I")
00786 _struct_2I = struct.Struct("<2I")
00787 _struct_3d = struct.Struct("<3d")