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


arm_navigation_msgs
Author(s): Gil Jones
autogenerated on Thu Dec 12 2013 11:08:10