_PlaceResult.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/PlaceResult.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 geometry_msgs.msg
00008 import object_manipulation_msgs.msg
00009 import std_msgs.msg
00010 
00011 class PlaceResult(genpy.Message):
00012   _md5sum = "531ddb04b8422b6734fb74421d431059"
00013   _type = "object_manipulation_msgs/PlaceResult"
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 
00017 # The result of the pickup attempt
00018 ManipulationResult manipulation_result
00019 
00020 # The successful place location, if any
00021 geometry_msgs/PoseStamped place_location
00022 
00023 # the list of attempted locations, in the order in which they were attempted
00024 # the successful one should be the last one in this list
00025 geometry_msgs/PoseStamped[] attempted_locations
00026 
00027 # the outcomes of the attempted locations, in the same order as attempted_locations
00028 PlaceLocationResult[] attempted_location_results
00029 
00030 
00031 ================================================================================
00032 MSG: object_manipulation_msgs/ManipulationResult
00033 # Result codes for manipulation tasks
00034 
00035 # task completed as expected
00036 # generally means you can proceed as planned
00037 int32 SUCCESS = 1
00038 
00039 # task not possible (e.g. out of reach or obstacles in the way)
00040 # generally means that the world was not disturbed, so you can try another task
00041 int32 UNFEASIBLE = -1
00042 
00043 # task was thought possible, but failed due to unexpected events during execution
00044 # it is likely that the world was disturbed, so you are encouraged to refresh
00045 # your sensed world model before proceeding to another task
00046 int32 FAILED = -2
00047 
00048 # a lower level error prevented task completion (e.g. joint controller not responding)
00049 # generally requires human attention
00050 int32 ERROR = -3
00051 
00052 # means that at some point during execution we ended up in a state that the collision-aware
00053 # arm navigation module will not move out of. The world was likely not disturbed, but you 
00054 # probably need a new collision map to move the arm out of the stuck position
00055 int32 ARM_MOVEMENT_PREVENTED = -4
00056 
00057 # specific to grasp actions
00058 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00059 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00060 int32 LIFT_FAILED = -5
00061 
00062 # specific to place actions
00063 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00064 # it is likely that the collision environment will see collisions between the hand and the object
00065 int32 RETREAT_FAILED = -6
00066 
00067 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00068 int32 CANCELLED = -7
00069 
00070 # the actual value of this error code
00071 int32 value
00072 
00073 ================================================================================
00074 MSG: geometry_msgs/PoseStamped
00075 # A Pose with reference coordinate frame and timestamp
00076 Header header
00077 Pose pose
00078 
00079 ================================================================================
00080 MSG: std_msgs/Header
00081 # Standard metadata for higher-level stamped data types.
00082 # This is generally used to communicate timestamped data 
00083 # in a particular coordinate frame.
00084 # 
00085 # sequence ID: consecutively increasing ID 
00086 uint32 seq
00087 #Two-integer timestamp that is expressed as:
00088 # * stamp.secs: seconds (stamp_secs) since epoch
00089 # * stamp.nsecs: nanoseconds since stamp_secs
00090 # time-handling sugar is provided by the client library
00091 time stamp
00092 #Frame this data is associated with
00093 # 0: no frame
00094 # 1: global frame
00095 string frame_id
00096 
00097 ================================================================================
00098 MSG: geometry_msgs/Pose
00099 # A representation of pose in free space, composed of postion and orientation. 
00100 Point position
00101 Quaternion orientation
00102 
00103 ================================================================================
00104 MSG: geometry_msgs/Point
00105 # This contains the position of a point in free space
00106 float64 x
00107 float64 y
00108 float64 z
00109 
00110 ================================================================================
00111 MSG: geometry_msgs/Quaternion
00112 # This represents an orientation in free space in quaternion form.
00113 
00114 float64 x
00115 float64 y
00116 float64 z
00117 float64 w
00118 
00119 ================================================================================
00120 MSG: object_manipulation_msgs/PlaceLocationResult
00121 int32 SUCCESS = 1
00122 int32 PLACE_OUT_OF_REACH = 2
00123 int32 PLACE_IN_COLLISION = 3
00124 int32 PLACE_UNFEASIBLE = 4
00125 int32 PREPLACE_OUT_OF_REACH = 5
00126 int32 PREPLACE_IN_COLLISION = 6
00127 int32 PREPLACE_UNFEASIBLE = 7
00128 int32 RETREAT_OUT_OF_REACH = 8
00129 int32 RETREAT_IN_COLLISION = 9
00130 int32 RETREAT_UNFEASIBLE = 10
00131 int32 MOVE_ARM_FAILED = 11
00132 int32 PLACE_FAILED = 12
00133 int32 RETREAT_FAILED = 13
00134 int32 result_code
00135 
00136 # whether the state of the world was disturbed by this attempt. generally, this flag
00137 # shows if another task can be attempted, or a new sensed world model is recommeded
00138 # before proceeding
00139 bool continuation_possible
00140 
00141 """
00142   __slots__ = ['manipulation_result','place_location','attempted_locations','attempted_location_results']
00143   _slot_types = ['object_manipulation_msgs/ManipulationResult','geometry_msgs/PoseStamped','geometry_msgs/PoseStamped[]','object_manipulation_msgs/PlaceLocationResult[]']
00144 
00145   def __init__(self, *args, **kwds):
00146     """
00147     Constructor. Any message fields that are implicitly/explicitly
00148     set to None will be assigned a default value. The recommend
00149     use is keyword arguments as this is more robust to future message
00150     changes.  You cannot mix in-order arguments and keyword arguments.
00151 
00152     The available fields are:
00153        manipulation_result,place_location,attempted_locations,attempted_location_results
00154 
00155     :param args: complete set of field values, in .msg order
00156     :param kwds: use keyword arguments corresponding to message field names
00157     to set specific fields.
00158     """
00159     if args or kwds:
00160       super(PlaceResult, self).__init__(*args, **kwds)
00161       #message fields cannot be None, assign default values for those that are
00162       if self.manipulation_result is None:
00163         self.manipulation_result = object_manipulation_msgs.msg.ManipulationResult()
00164       if self.place_location is None:
00165         self.place_location = geometry_msgs.msg.PoseStamped()
00166       if self.attempted_locations is None:
00167         self.attempted_locations = []
00168       if self.attempted_location_results is None:
00169         self.attempted_location_results = []
00170     else:
00171       self.manipulation_result = object_manipulation_msgs.msg.ManipulationResult()
00172       self.place_location = geometry_msgs.msg.PoseStamped()
00173       self.attempted_locations = []
00174       self.attempted_location_results = []
00175 
00176   def _get_types(self):
00177     """
00178     internal API method
00179     """
00180     return self._slot_types
00181 
00182   def serialize(self, buff):
00183     """
00184     serialize message into buffer
00185     :param buff: buffer, ``StringIO``
00186     """
00187     try:
00188       _x = self
00189       buff.write(_struct_i3I.pack(_x.manipulation_result.value, _x.place_location.header.seq, _x.place_location.header.stamp.secs, _x.place_location.header.stamp.nsecs))
00190       _x = self.place_location.header.frame_id
00191       length = len(_x)
00192       if python3 or type(_x) == unicode:
00193         _x = _x.encode('utf-8')
00194         length = len(_x)
00195       buff.write(struct.pack('<I%ss'%length, length, _x))
00196       _x = self
00197       buff.write(_struct_7d.pack(_x.place_location.pose.position.x, _x.place_location.pose.position.y, _x.place_location.pose.position.z, _x.place_location.pose.orientation.x, _x.place_location.pose.orientation.y, _x.place_location.pose.orientation.z, _x.place_location.pose.orientation.w))
00198       length = len(self.attempted_locations)
00199       buff.write(_struct_I.pack(length))
00200       for val1 in self.attempted_locations:
00201         _v1 = val1.header
00202         buff.write(_struct_I.pack(_v1.seq))
00203         _v2 = _v1.stamp
00204         _x = _v2
00205         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00206         _x = _v1.frame_id
00207         length = len(_x)
00208         if python3 or type(_x) == unicode:
00209           _x = _x.encode('utf-8')
00210           length = len(_x)
00211         buff.write(struct.pack('<I%ss'%length, length, _x))
00212         _v3 = val1.pose
00213         _v4 = _v3.position
00214         _x = _v4
00215         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00216         _v5 = _v3.orientation
00217         _x = _v5
00218         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00219       length = len(self.attempted_location_results)
00220       buff.write(_struct_I.pack(length))
00221       for val1 in self.attempted_location_results:
00222         _x = val1
00223         buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
00224     except struct.error as se: self._check_types(se)
00225     except TypeError as te: self._check_types(te)
00226 
00227   def deserialize(self, str):
00228     """
00229     unpack serialized message in str into this message instance
00230     :param str: byte array of serialized message, ``str``
00231     """
00232     try:
00233       if self.manipulation_result is None:
00234         self.manipulation_result = object_manipulation_msgs.msg.ManipulationResult()
00235       if self.place_location is None:
00236         self.place_location = geometry_msgs.msg.PoseStamped()
00237       if self.attempted_locations is None:
00238         self.attempted_locations = None
00239       if self.attempted_location_results is None:
00240         self.attempted_location_results = None
00241       end = 0
00242       _x = self
00243       start = end
00244       end += 16
00245       (_x.manipulation_result.value, _x.place_location.header.seq, _x.place_location.header.stamp.secs, _x.place_location.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00246       start = end
00247       end += 4
00248       (length,) = _struct_I.unpack(str[start:end])
00249       start = end
00250       end += length
00251       if python3:
00252         self.place_location.header.frame_id = str[start:end].decode('utf-8')
00253       else:
00254         self.place_location.header.frame_id = str[start:end]
00255       _x = self
00256       start = end
00257       end += 56
00258       (_x.place_location.pose.position.x, _x.place_location.pose.position.y, _x.place_location.pose.position.z, _x.place_location.pose.orientation.x, _x.place_location.pose.orientation.y, _x.place_location.pose.orientation.z, _x.place_location.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00259       start = end
00260       end += 4
00261       (length,) = _struct_I.unpack(str[start:end])
00262       self.attempted_locations = []
00263       for i in range(0, length):
00264         val1 = geometry_msgs.msg.PoseStamped()
00265         _v6 = val1.header
00266         start = end
00267         end += 4
00268         (_v6.seq,) = _struct_I.unpack(str[start:end])
00269         _v7 = _v6.stamp
00270         _x = _v7
00271         start = end
00272         end += 8
00273         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00274         start = end
00275         end += 4
00276         (length,) = _struct_I.unpack(str[start:end])
00277         start = end
00278         end += length
00279         if python3:
00280           _v6.frame_id = str[start:end].decode('utf-8')
00281         else:
00282           _v6.frame_id = str[start:end]
00283         _v8 = val1.pose
00284         _v9 = _v8.position
00285         _x = _v9
00286         start = end
00287         end += 24
00288         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00289         _v10 = _v8.orientation
00290         _x = _v10
00291         start = end
00292         end += 32
00293         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00294         self.attempted_locations.append(val1)
00295       start = end
00296       end += 4
00297       (length,) = _struct_I.unpack(str[start:end])
00298       self.attempted_location_results = []
00299       for i in range(0, length):
00300         val1 = object_manipulation_msgs.msg.PlaceLocationResult()
00301         _x = val1
00302         start = end
00303         end += 5
00304         (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
00305         val1.continuation_possible = bool(val1.continuation_possible)
00306         self.attempted_location_results.append(val1)
00307       return self
00308     except struct.error as e:
00309       raise genpy.DeserializationError(e) #most likely buffer underfill
00310 
00311 
00312   def serialize_numpy(self, buff, numpy):
00313     """
00314     serialize message with numpy array types into buffer
00315     :param buff: buffer, ``StringIO``
00316     :param numpy: numpy python module
00317     """
00318     try:
00319       _x = self
00320       buff.write(_struct_i3I.pack(_x.manipulation_result.value, _x.place_location.header.seq, _x.place_location.header.stamp.secs, _x.place_location.header.stamp.nsecs))
00321       _x = self.place_location.header.frame_id
00322       length = len(_x)
00323       if python3 or type(_x) == unicode:
00324         _x = _x.encode('utf-8')
00325         length = len(_x)
00326       buff.write(struct.pack('<I%ss'%length, length, _x))
00327       _x = self
00328       buff.write(_struct_7d.pack(_x.place_location.pose.position.x, _x.place_location.pose.position.y, _x.place_location.pose.position.z, _x.place_location.pose.orientation.x, _x.place_location.pose.orientation.y, _x.place_location.pose.orientation.z, _x.place_location.pose.orientation.w))
00329       length = len(self.attempted_locations)
00330       buff.write(_struct_I.pack(length))
00331       for val1 in self.attempted_locations:
00332         _v11 = val1.header
00333         buff.write(_struct_I.pack(_v11.seq))
00334         _v12 = _v11.stamp
00335         _x = _v12
00336         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00337         _x = _v11.frame_id
00338         length = len(_x)
00339         if python3 or type(_x) == unicode:
00340           _x = _x.encode('utf-8')
00341           length = len(_x)
00342         buff.write(struct.pack('<I%ss'%length, length, _x))
00343         _v13 = val1.pose
00344         _v14 = _v13.position
00345         _x = _v14
00346         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00347         _v15 = _v13.orientation
00348         _x = _v15
00349         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00350       length = len(self.attempted_location_results)
00351       buff.write(_struct_I.pack(length))
00352       for val1 in self.attempted_location_results:
00353         _x = val1
00354         buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
00355     except struct.error as se: self._check_types(se)
00356     except TypeError as te: self._check_types(te)
00357 
00358   def deserialize_numpy(self, str, numpy):
00359     """
00360     unpack serialized message in str into this message instance using numpy for array types
00361     :param str: byte array of serialized message, ``str``
00362     :param numpy: numpy python module
00363     """
00364     try:
00365       if self.manipulation_result is None:
00366         self.manipulation_result = object_manipulation_msgs.msg.ManipulationResult()
00367       if self.place_location is None:
00368         self.place_location = geometry_msgs.msg.PoseStamped()
00369       if self.attempted_locations is None:
00370         self.attempted_locations = None
00371       if self.attempted_location_results is None:
00372         self.attempted_location_results = None
00373       end = 0
00374       _x = self
00375       start = end
00376       end += 16
00377       (_x.manipulation_result.value, _x.place_location.header.seq, _x.place_location.header.stamp.secs, _x.place_location.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00378       start = end
00379       end += 4
00380       (length,) = _struct_I.unpack(str[start:end])
00381       start = end
00382       end += length
00383       if python3:
00384         self.place_location.header.frame_id = str[start:end].decode('utf-8')
00385       else:
00386         self.place_location.header.frame_id = str[start:end]
00387       _x = self
00388       start = end
00389       end += 56
00390       (_x.place_location.pose.position.x, _x.place_location.pose.position.y, _x.place_location.pose.position.z, _x.place_location.pose.orientation.x, _x.place_location.pose.orientation.y, _x.place_location.pose.orientation.z, _x.place_location.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00391       start = end
00392       end += 4
00393       (length,) = _struct_I.unpack(str[start:end])
00394       self.attempted_locations = []
00395       for i in range(0, length):
00396         val1 = geometry_msgs.msg.PoseStamped()
00397         _v16 = val1.header
00398         start = end
00399         end += 4
00400         (_v16.seq,) = _struct_I.unpack(str[start:end])
00401         _v17 = _v16.stamp
00402         _x = _v17
00403         start = end
00404         end += 8
00405         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00406         start = end
00407         end += 4
00408         (length,) = _struct_I.unpack(str[start:end])
00409         start = end
00410         end += length
00411         if python3:
00412           _v16.frame_id = str[start:end].decode('utf-8')
00413         else:
00414           _v16.frame_id = str[start:end]
00415         _v18 = val1.pose
00416         _v19 = _v18.position
00417         _x = _v19
00418         start = end
00419         end += 24
00420         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00421         _v20 = _v18.orientation
00422         _x = _v20
00423         start = end
00424         end += 32
00425         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00426         self.attempted_locations.append(val1)
00427       start = end
00428       end += 4
00429       (length,) = _struct_I.unpack(str[start:end])
00430       self.attempted_location_results = []
00431       for i in range(0, length):
00432         val1 = object_manipulation_msgs.msg.PlaceLocationResult()
00433         _x = val1
00434         start = end
00435         end += 5
00436         (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
00437         val1.continuation_possible = bool(val1.continuation_possible)
00438         self.attempted_location_results.append(val1)
00439       return self
00440     except struct.error as e:
00441       raise genpy.DeserializationError(e) #most likely buffer underfill
00442 
00443 _struct_I = genpy.struct_I
00444 _struct_7d = struct.Struct("<7d")
00445 _struct_i3I = struct.Struct("<i3I")
00446 _struct_4d = struct.Struct("<4d")
00447 _struct_iB = struct.Struct("<iB")
00448 _struct_2I = struct.Struct("<2I")
00449 _struct_3d = struct.Struct("<3d")


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Thu Jan 2 2014 11:38:12