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