$search
00001 """autogenerated by genmsg_py from MoveArmActionResult.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import arm_navigation_msgs.msg 00006 import geometry_msgs.msg 00007 import roslib.rostime 00008 import actionlib_msgs.msg 00009 import std_msgs.msg 00010 00011 class MoveArmActionResult(roslib.message.Message): 00012 _md5sum = "3e2bd2d3bd64d9942c0ef04de381c628" 00013 _type = "arm_navigation_msgs/MoveArmActionResult" 00014 _has_header = True #flag to mark the presence of a Header object 00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00016 00017 Header header 00018 actionlib_msgs/GoalStatus status 00019 MoveArmResult result 00020 00021 ================================================================================ 00022 MSG: std_msgs/Header 00023 # Standard metadata for higher-level stamped data types. 00024 # This is generally used to communicate timestamped data 00025 # in a particular coordinate frame. 00026 # 00027 # sequence ID: consecutively increasing ID 00028 uint32 seq 00029 #Two-integer timestamp that is expressed as: 00030 # * stamp.secs: seconds (stamp_secs) since epoch 00031 # * stamp.nsecs: nanoseconds since stamp_secs 00032 # time-handling sugar is provided by the client library 00033 time stamp 00034 #Frame this data is associated with 00035 # 0: no frame 00036 # 1: global frame 00037 string frame_id 00038 00039 ================================================================================ 00040 MSG: actionlib_msgs/GoalStatus 00041 GoalID goal_id 00042 uint8 status 00043 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00044 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00045 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00046 # and has since completed its execution (Terminal State) 00047 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00048 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00049 # to some failure (Terminal State) 00050 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00051 # because the goal was unattainable or invalid (Terminal State) 00052 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00053 # and has not yet completed execution 00054 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00055 # but the action server has not yet confirmed that the goal is canceled 00056 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00057 # and was successfully cancelled (Terminal State) 00058 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00059 # sent over the wire by an action server 00060 00061 #Allow for the user to associate a string with GoalStatus for debugging 00062 string text 00063 00064 00065 ================================================================================ 00066 MSG: actionlib_msgs/GoalID 00067 # The stamp should store the time at which this goal was requested. 00068 # It is used by an action server when it tries to preempt all 00069 # goals that were requested before a certain time 00070 time stamp 00071 00072 # The id provides a way to associate feedback and 00073 # result message with specific goal requests. The id 00074 # specified must be unique. 00075 string id 00076 00077 00078 ================================================================================ 00079 MSG: arm_navigation_msgs/MoveArmResult 00080 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00081 # An error code reflecting what went wrong 00082 ArmNavigationErrorCodes error_code 00083 00084 ContactInformation[] contacts 00085 00086 ================================================================================ 00087 MSG: arm_navigation_msgs/ArmNavigationErrorCodes 00088 int32 val 00089 00090 # overall behavior 00091 int32 PLANNING_FAILED=-1 00092 int32 SUCCESS=1 00093 int32 TIMED_OUT=-2 00094 00095 # start state errors 00096 int32 START_STATE_IN_COLLISION=-3 00097 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4 00098 00099 # goal errors 00100 int32 GOAL_IN_COLLISION=-5 00101 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6 00102 00103 # robot state 00104 int32 INVALID_ROBOT_STATE=-7 00105 int32 INCOMPLETE_ROBOT_STATE=-8 00106 00107 # planning request errors 00108 int32 INVALID_PLANNER_ID=-9 00109 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10 00110 int32 INVALID_ALLOWED_PLANNING_TIME=-11 00111 int32 INVALID_GROUP_NAME=-12 00112 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13 00113 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14 00114 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15 00115 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16 00116 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17 00117 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18 00118 00119 # state/trajectory monitor errors 00120 int32 INVALID_TRAJECTORY=-19 00121 int32 INVALID_INDEX=-20 00122 int32 JOINT_LIMITS_VIOLATED=-21 00123 int32 PATH_CONSTRAINTS_VIOLATED=-22 00124 int32 COLLISION_CONSTRAINTS_VIOLATED=-23 00125 int32 GOAL_CONSTRAINTS_VIOLATED=-24 00126 int32 JOINTS_NOT_MOVING=-25 00127 int32 TRAJECTORY_CONTROLLER_FAILED=-26 00128 00129 # system errors 00130 int32 FRAME_TRANSFORM_FAILURE=-27 00131 int32 COLLISION_CHECKING_UNAVAILABLE=-28 00132 int32 ROBOT_STATE_STALE=-29 00133 int32 SENSOR_INFO_STALE=-30 00134 00135 # kinematics errors 00136 int32 NO_IK_SOLUTION=-31 00137 int32 INVALID_LINK_NAME=-32 00138 int32 IK_LINK_IN_COLLISION=-33 00139 int32 NO_FK_SOLUTION=-34 00140 int32 KINEMATICS_STATE_IN_COLLISION=-35 00141 00142 # general errors 00143 int32 INVALID_TIMEOUT=-36 00144 00145 00146 ================================================================================ 00147 MSG: arm_navigation_msgs/ContactInformation 00148 # Standard ROS header contains information 00149 # about the frame in which this 00150 # contact is specified 00151 Header header 00152 00153 # Position of the contact point 00154 geometry_msgs/Point position 00155 00156 # Normal corresponding to the contact point 00157 geometry_msgs/Vector3 normal 00158 00159 # Depth of contact point 00160 float64 depth 00161 00162 # Name of the first body that is in contact 00163 # This could be a link or a namespace that represents a body 00164 string contact_body_1 00165 string attached_body_1 00166 uint32 body_type_1 00167 00168 # Name of the second body that is in contact 00169 # This could be a link or a namespace that represents a body 00170 string contact_body_2 00171 string attached_body_2 00172 uint32 body_type_2 00173 00174 uint32 ROBOT_LINK=0 00175 uint32 OBJECT=1 00176 uint32 ATTACHED_BODY=2 00177 ================================================================================ 00178 MSG: geometry_msgs/Point 00179 # This contains the position of a point in free space 00180 float64 x 00181 float64 y 00182 float64 z 00183 00184 ================================================================================ 00185 MSG: geometry_msgs/Vector3 00186 # This represents a vector in free space. 00187 00188 float64 x 00189 float64 y 00190 float64 z 00191 """ 00192 __slots__ = ['header','status','result'] 00193 _slot_types = ['Header','actionlib_msgs/GoalStatus','arm_navigation_msgs/MoveArmResult'] 00194 00195 def __init__(self, *args, **kwds): 00196 """ 00197 Constructor. Any message fields that are implicitly/explicitly 00198 set to None will be assigned a default value. The recommend 00199 use is keyword arguments as this is more robust to future message 00200 changes. You cannot mix in-order arguments and keyword arguments. 00201 00202 The available fields are: 00203 header,status,result 00204 00205 @param args: complete set of field values, in .msg order 00206 @param kwds: use keyword arguments corresponding to message field names 00207 to set specific fields. 00208 """ 00209 if args or kwds: 00210 super(MoveArmActionResult, self).__init__(*args, **kwds) 00211 #message fields cannot be None, assign default values for those that are 00212 if self.header is None: 00213 self.header = std_msgs.msg._Header.Header() 00214 if self.status is None: 00215 self.status = actionlib_msgs.msg.GoalStatus() 00216 if self.result is None: 00217 self.result = arm_navigation_msgs.msg.MoveArmResult() 00218 else: 00219 self.header = std_msgs.msg._Header.Header() 00220 self.status = actionlib_msgs.msg.GoalStatus() 00221 self.result = arm_navigation_msgs.msg.MoveArmResult() 00222 00223 def _get_types(self): 00224 """ 00225 internal API method 00226 """ 00227 return self._slot_types 00228 00229 def serialize(self, buff): 00230 """ 00231 serialize message into buffer 00232 @param buff: buffer 00233 @type buff: StringIO 00234 """ 00235 try: 00236 _x = self 00237 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00238 _x = self.header.frame_id 00239 length = len(_x) 00240 buff.write(struct.pack('<I%ss'%length, length, _x)) 00241 _x = self 00242 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00243 _x = self.status.goal_id.id 00244 length = len(_x) 00245 buff.write(struct.pack('<I%ss'%length, length, _x)) 00246 buff.write(_struct_B.pack(self.status.status)) 00247 _x = self.status.text 00248 length = len(_x) 00249 buff.write(struct.pack('<I%ss'%length, length, _x)) 00250 buff.write(_struct_i.pack(self.result.error_code.val)) 00251 length = len(self.result.contacts) 00252 buff.write(_struct_I.pack(length)) 00253 for val1 in self.result.contacts: 00254 _v1 = val1.header 00255 buff.write(_struct_I.pack(_v1.seq)) 00256 _v2 = _v1.stamp 00257 _x = _v2 00258 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00259 _x = _v1.frame_id 00260 length = len(_x) 00261 buff.write(struct.pack('<I%ss'%length, length, _x)) 00262 _v3 = val1.position 00263 _x = _v3 00264 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00265 _v4 = val1.normal 00266 _x = _v4 00267 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00268 buff.write(_struct_d.pack(val1.depth)) 00269 _x = val1.contact_body_1 00270 length = len(_x) 00271 buff.write(struct.pack('<I%ss'%length, length, _x)) 00272 _x = val1.attached_body_1 00273 length = len(_x) 00274 buff.write(struct.pack('<I%ss'%length, length, _x)) 00275 buff.write(_struct_I.pack(val1.body_type_1)) 00276 _x = val1.contact_body_2 00277 length = len(_x) 00278 buff.write(struct.pack('<I%ss'%length, length, _x)) 00279 _x = val1.attached_body_2 00280 length = len(_x) 00281 buff.write(struct.pack('<I%ss'%length, length, _x)) 00282 buff.write(_struct_I.pack(val1.body_type_2)) 00283 except struct.error as se: self._check_types(se) 00284 except TypeError as te: self._check_types(te) 00285 00286 def deserialize(self, str): 00287 """ 00288 unpack serialized message in str into this message instance 00289 @param str: byte array of serialized message 00290 @type str: str 00291 """ 00292 try: 00293 if self.header is None: 00294 self.header = std_msgs.msg._Header.Header() 00295 if self.status is None: 00296 self.status = actionlib_msgs.msg.GoalStatus() 00297 if self.result is None: 00298 self.result = arm_navigation_msgs.msg.MoveArmResult() 00299 end = 0 00300 _x = self 00301 start = end 00302 end += 12 00303 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00304 start = end 00305 end += 4 00306 (length,) = _struct_I.unpack(str[start:end]) 00307 start = end 00308 end += length 00309 self.header.frame_id = str[start:end] 00310 _x = self 00311 start = end 00312 end += 8 00313 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00314 start = end 00315 end += 4 00316 (length,) = _struct_I.unpack(str[start:end]) 00317 start = end 00318 end += length 00319 self.status.goal_id.id = str[start:end] 00320 start = end 00321 end += 1 00322 (self.status.status,) = _struct_B.unpack(str[start:end]) 00323 start = end 00324 end += 4 00325 (length,) = _struct_I.unpack(str[start:end]) 00326 start = end 00327 end += length 00328 self.status.text = str[start:end] 00329 start = end 00330 end += 4 00331 (self.result.error_code.val,) = _struct_i.unpack(str[start:end]) 00332 start = end 00333 end += 4 00334 (length,) = _struct_I.unpack(str[start:end]) 00335 self.result.contacts = [] 00336 for i in range(0, length): 00337 val1 = arm_navigation_msgs.msg.ContactInformation() 00338 _v5 = val1.header 00339 start = end 00340 end += 4 00341 (_v5.seq,) = _struct_I.unpack(str[start:end]) 00342 _v6 = _v5.stamp 00343 _x = _v6 00344 start = end 00345 end += 8 00346 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00347 start = end 00348 end += 4 00349 (length,) = _struct_I.unpack(str[start:end]) 00350 start = end 00351 end += length 00352 _v5.frame_id = str[start:end] 00353 _v7 = val1.position 00354 _x = _v7 00355 start = end 00356 end += 24 00357 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00358 _v8 = val1.normal 00359 _x = _v8 00360 start = end 00361 end += 24 00362 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00363 start = end 00364 end += 8 00365 (val1.depth,) = _struct_d.unpack(str[start:end]) 00366 start = end 00367 end += 4 00368 (length,) = _struct_I.unpack(str[start:end]) 00369 start = end 00370 end += length 00371 val1.contact_body_1 = str[start:end] 00372 start = end 00373 end += 4 00374 (length,) = _struct_I.unpack(str[start:end]) 00375 start = end 00376 end += length 00377 val1.attached_body_1 = str[start:end] 00378 start = end 00379 end += 4 00380 (val1.body_type_1,) = _struct_I.unpack(str[start:end]) 00381 start = end 00382 end += 4 00383 (length,) = _struct_I.unpack(str[start:end]) 00384 start = end 00385 end += length 00386 val1.contact_body_2 = str[start:end] 00387 start = end 00388 end += 4 00389 (length,) = _struct_I.unpack(str[start:end]) 00390 start = end 00391 end += length 00392 val1.attached_body_2 = str[start:end] 00393 start = end 00394 end += 4 00395 (val1.body_type_2,) = _struct_I.unpack(str[start:end]) 00396 self.result.contacts.append(val1) 00397 return self 00398 except struct.error as e: 00399 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00400 00401 00402 def serialize_numpy(self, buff, numpy): 00403 """ 00404 serialize message with numpy array types into buffer 00405 @param buff: buffer 00406 @type buff: StringIO 00407 @param numpy: numpy python module 00408 @type numpy module 00409 """ 00410 try: 00411 _x = self 00412 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00413 _x = self.header.frame_id 00414 length = len(_x) 00415 buff.write(struct.pack('<I%ss'%length, length, _x)) 00416 _x = self 00417 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00418 _x = self.status.goal_id.id 00419 length = len(_x) 00420 buff.write(struct.pack('<I%ss'%length, length, _x)) 00421 buff.write(_struct_B.pack(self.status.status)) 00422 _x = self.status.text 00423 length = len(_x) 00424 buff.write(struct.pack('<I%ss'%length, length, _x)) 00425 buff.write(_struct_i.pack(self.result.error_code.val)) 00426 length = len(self.result.contacts) 00427 buff.write(_struct_I.pack(length)) 00428 for val1 in self.result.contacts: 00429 _v9 = val1.header 00430 buff.write(_struct_I.pack(_v9.seq)) 00431 _v10 = _v9.stamp 00432 _x = _v10 00433 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00434 _x = _v9.frame_id 00435 length = len(_x) 00436 buff.write(struct.pack('<I%ss'%length, length, _x)) 00437 _v11 = val1.position 00438 _x = _v11 00439 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00440 _v12 = val1.normal 00441 _x = _v12 00442 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00443 buff.write(_struct_d.pack(val1.depth)) 00444 _x = val1.contact_body_1 00445 length = len(_x) 00446 buff.write(struct.pack('<I%ss'%length, length, _x)) 00447 _x = val1.attached_body_1 00448 length = len(_x) 00449 buff.write(struct.pack('<I%ss'%length, length, _x)) 00450 buff.write(_struct_I.pack(val1.body_type_1)) 00451 _x = val1.contact_body_2 00452 length = len(_x) 00453 buff.write(struct.pack('<I%ss'%length, length, _x)) 00454 _x = val1.attached_body_2 00455 length = len(_x) 00456 buff.write(struct.pack('<I%ss'%length, length, _x)) 00457 buff.write(_struct_I.pack(val1.body_type_2)) 00458 except struct.error as se: self._check_types(se) 00459 except TypeError as te: self._check_types(te) 00460 00461 def deserialize_numpy(self, str, numpy): 00462 """ 00463 unpack serialized message in str into this message instance using numpy for array types 00464 @param str: byte array of serialized message 00465 @type str: str 00466 @param numpy: numpy python module 00467 @type numpy: module 00468 """ 00469 try: 00470 if self.header is None: 00471 self.header = std_msgs.msg._Header.Header() 00472 if self.status is None: 00473 self.status = actionlib_msgs.msg.GoalStatus() 00474 if self.result is None: 00475 self.result = arm_navigation_msgs.msg.MoveArmResult() 00476 end = 0 00477 _x = self 00478 start = end 00479 end += 12 00480 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00481 start = end 00482 end += 4 00483 (length,) = _struct_I.unpack(str[start:end]) 00484 start = end 00485 end += length 00486 self.header.frame_id = str[start:end] 00487 _x = self 00488 start = end 00489 end += 8 00490 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00491 start = end 00492 end += 4 00493 (length,) = _struct_I.unpack(str[start:end]) 00494 start = end 00495 end += length 00496 self.status.goal_id.id = str[start:end] 00497 start = end 00498 end += 1 00499 (self.status.status,) = _struct_B.unpack(str[start:end]) 00500 start = end 00501 end += 4 00502 (length,) = _struct_I.unpack(str[start:end]) 00503 start = end 00504 end += length 00505 self.status.text = str[start:end] 00506 start = end 00507 end += 4 00508 (self.result.error_code.val,) = _struct_i.unpack(str[start:end]) 00509 start = end 00510 end += 4 00511 (length,) = _struct_I.unpack(str[start:end]) 00512 self.result.contacts = [] 00513 for i in range(0, length): 00514 val1 = arm_navigation_msgs.msg.ContactInformation() 00515 _v13 = val1.header 00516 start = end 00517 end += 4 00518 (_v13.seq,) = _struct_I.unpack(str[start:end]) 00519 _v14 = _v13.stamp 00520 _x = _v14 00521 start = end 00522 end += 8 00523 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00524 start = end 00525 end += 4 00526 (length,) = _struct_I.unpack(str[start:end]) 00527 start = end 00528 end += length 00529 _v13.frame_id = str[start:end] 00530 _v15 = val1.position 00531 _x = _v15 00532 start = end 00533 end += 24 00534 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00535 _v16 = val1.normal 00536 _x = _v16 00537 start = end 00538 end += 24 00539 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00540 start = end 00541 end += 8 00542 (val1.depth,) = _struct_d.unpack(str[start:end]) 00543 start = end 00544 end += 4 00545 (length,) = _struct_I.unpack(str[start:end]) 00546 start = end 00547 end += length 00548 val1.contact_body_1 = str[start:end] 00549 start = end 00550 end += 4 00551 (length,) = _struct_I.unpack(str[start:end]) 00552 start = end 00553 end += length 00554 val1.attached_body_1 = str[start:end] 00555 start = end 00556 end += 4 00557 (val1.body_type_1,) = _struct_I.unpack(str[start:end]) 00558 start = end 00559 end += 4 00560 (length,) = _struct_I.unpack(str[start:end]) 00561 start = end 00562 end += length 00563 val1.contact_body_2 = str[start:end] 00564 start = end 00565 end += 4 00566 (length,) = _struct_I.unpack(str[start:end]) 00567 start = end 00568 end += length 00569 val1.attached_body_2 = str[start:end] 00570 start = end 00571 end += 4 00572 (val1.body_type_2,) = _struct_I.unpack(str[start:end]) 00573 self.result.contacts.append(val1) 00574 return self 00575 except struct.error as e: 00576 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00577 00578 _struct_I = roslib.message.struct_I 00579 _struct_B = struct.Struct("<B") 00580 _struct_d = struct.Struct("<d") 00581 _struct_i = struct.Struct("<i") 00582 _struct_3I = struct.Struct("<3I") 00583 _struct_2I = struct.Struct("<2I") 00584 _struct_3d = struct.Struct("<3d")