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