_AttachedCollisionObject.py
Go to the documentation of this file.
00001 """autogenerated by genpy from arm_navigation_msgs/AttachedCollisionObject.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 AttachedCollisionObject(genpy.Message):
00012   _md5sum = "3fd8ca730863e3d97d109c317d106cf9"
00013   _type = "arm_navigation_msgs/AttachedCollisionObject"
00014   _has_header = False #flag to mark the presence of a Header object
00015   _full_text = """# The CollisionObject will be attached with a fixed joint to this link
00016 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation 
00017 # is set to REMOVE will remove all attached bodies attached to any object
00018 string link_name
00019 
00020 #Reserved for indicating that all attached objects should be removed
00021 string REMOVE_ALL_ATTACHED_OBJECTS = "all"
00022 
00023 #This contains the actual shapes and poses for the CollisionObject
00024 #to be attached to the link
00025 #If action is remove and no object.id is set, all objects
00026 #attached to the link indicated by link_name will be removed
00027 CollisionObject object
00028 
00029 # The set of links that the attached objects are allowed to touch
00030 # by default - the link_name is included by default
00031 string[] touch_links
00032 
00033 ================================================================================
00034 MSG: arm_navigation_msgs/CollisionObject
00035 # a header, used for interpreting the poses
00036 Header header
00037 
00038 # the id of the object
00039 string id
00040 
00041 # The padding used for filtering points near the object.
00042 # This does not affect collision checking for the object.  
00043 # Set to negative to get zero padding.
00044 float32 padding
00045 
00046 #This contains what is to be done with the object
00047 CollisionObjectOperation operation
00048 
00049 #the shapes associated with the object
00050 arm_navigation_msgs/Shape[] shapes
00051 
00052 #the poses associated with the shapes - will be transformed using the header
00053 geometry_msgs/Pose[] poses
00054 
00055 ================================================================================
00056 MSG: std_msgs/Header
00057 # Standard metadata for higher-level stamped data types.
00058 # This is generally used to communicate timestamped data 
00059 # in a particular coordinate frame.
00060 # 
00061 # sequence ID: consecutively increasing ID 
00062 uint32 seq
00063 #Two-integer timestamp that is expressed as:
00064 # * stamp.secs: seconds (stamp_secs) since epoch
00065 # * stamp.nsecs: nanoseconds since stamp_secs
00066 # time-handling sugar is provided by the client library
00067 time stamp
00068 #Frame this data is associated with
00069 # 0: no frame
00070 # 1: global frame
00071 string frame_id
00072 
00073 ================================================================================
00074 MSG: arm_navigation_msgs/CollisionObjectOperation
00075 #Puts the object into the environment
00076 #or updates the object if already added
00077 byte ADD=0
00078 
00079 #Removes the object from the environment entirely
00080 byte REMOVE=1
00081 
00082 #Only valid within the context of a CollisionAttachedObject message
00083 #Will be ignored if sent with an CollisionObject message
00084 #Takes an attached object, detaches from the attached link
00085 #But adds back in as regular object
00086 byte DETACH_AND_ADD_AS_OBJECT=2
00087 
00088 #Only valid within the context of a CollisionAttachedObject message
00089 #Will be ignored if sent with an CollisionObject message
00090 #Takes current object in the environment and removes it as
00091 #a regular object
00092 byte ATTACH_AND_REMOVE_AS_OBJECT=3
00093 
00094 # Byte code for operation
00095 byte operation
00096 
00097 ================================================================================
00098 MSG: arm_navigation_msgs/Shape
00099 byte SPHERE=0
00100 byte BOX=1
00101 byte CYLINDER=2
00102 byte MESH=3
00103 
00104 byte type
00105 
00106 
00107 #### define sphere, box, cylinder ####
00108 # the origin of each shape is considered at the shape's center
00109 
00110 # for sphere
00111 # radius := dimensions[0]
00112 
00113 # for cylinder
00114 # radius := dimensions[0]
00115 # length := dimensions[1]
00116 # the length is along the Z axis
00117 
00118 # for box
00119 # size_x := dimensions[0]
00120 # size_y := dimensions[1]
00121 # size_z := dimensions[2]
00122 float64[] dimensions
00123 
00124 
00125 #### define mesh ####
00126 
00127 # list of triangles; triangle k is defined by tre vertices located
00128 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00129 int32[] triangles
00130 geometry_msgs/Point[] vertices
00131 
00132 ================================================================================
00133 MSG: geometry_msgs/Point
00134 # This contains the position of a point in free space
00135 float64 x
00136 float64 y
00137 float64 z
00138 
00139 ================================================================================
00140 MSG: geometry_msgs/Pose
00141 # A representation of pose in free space, composed of postion and orientation. 
00142 Point position
00143 Quaternion orientation
00144 
00145 ================================================================================
00146 MSG: geometry_msgs/Quaternion
00147 # This represents an orientation in free space in quaternion form.
00148 
00149 float64 x
00150 float64 y
00151 float64 z
00152 float64 w
00153 
00154 """
00155   # Pseudo-constants
00156   REMOVE_ALL_ATTACHED_OBJECTS = r'"all"'
00157 
00158   __slots__ = ['link_name','object','touch_links']
00159   _slot_types = ['string','arm_navigation_msgs/CollisionObject','string[]']
00160 
00161   def __init__(self, *args, **kwds):
00162     """
00163     Constructor. Any message fields that are implicitly/explicitly
00164     set to None will be assigned a default value. The recommend
00165     use is keyword arguments as this is more robust to future message
00166     changes.  You cannot mix in-order arguments and keyword arguments.
00167 
00168     The available fields are:
00169        link_name,object,touch_links
00170 
00171     :param args: complete set of field values, in .msg order
00172     :param kwds: use keyword arguments corresponding to message field names
00173     to set specific fields.
00174     """
00175     if args or kwds:
00176       super(AttachedCollisionObject, self).__init__(*args, **kwds)
00177       #message fields cannot be None, assign default values for those that are
00178       if self.link_name is None:
00179         self.link_name = ''
00180       if self.object is None:
00181         self.object = arm_navigation_msgs.msg.CollisionObject()
00182       if self.touch_links is None:
00183         self.touch_links = []
00184     else:
00185       self.link_name = ''
00186       self.object = arm_navigation_msgs.msg.CollisionObject()
00187       self.touch_links = []
00188 
00189   def _get_types(self):
00190     """
00191     internal API method
00192     """
00193     return self._slot_types
00194 
00195   def serialize(self, buff):
00196     """
00197     serialize message into buffer
00198     :param buff: buffer, ``StringIO``
00199     """
00200     try:
00201       _x = self.link_name
00202       length = len(_x)
00203       if python3 or type(_x) == unicode:
00204         _x = _x.encode('utf-8')
00205         length = len(_x)
00206       buff.write(struct.pack('<I%ss'%length, length, _x))
00207       _x = self
00208       buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
00209       _x = self.object.header.frame_id
00210       length = len(_x)
00211       if python3 or type(_x) == unicode:
00212         _x = _x.encode('utf-8')
00213         length = len(_x)
00214       buff.write(struct.pack('<I%ss'%length, length, _x))
00215       _x = self.object.id
00216       length = len(_x)
00217       if python3 or type(_x) == unicode:
00218         _x = _x.encode('utf-8')
00219         length = len(_x)
00220       buff.write(struct.pack('<I%ss'%length, length, _x))
00221       _x = self
00222       buff.write(_struct_fb.pack(_x.object.padding, _x.object.operation.operation))
00223       length = len(self.object.shapes)
00224       buff.write(_struct_I.pack(length))
00225       for val1 in self.object.shapes:
00226         buff.write(_struct_b.pack(val1.type))
00227         length = len(val1.dimensions)
00228         buff.write(_struct_I.pack(length))
00229         pattern = '<%sd'%length
00230         buff.write(struct.pack(pattern, *val1.dimensions))
00231         length = len(val1.triangles)
00232         buff.write(_struct_I.pack(length))
00233         pattern = '<%si'%length
00234         buff.write(struct.pack(pattern, *val1.triangles))
00235         length = len(val1.vertices)
00236         buff.write(_struct_I.pack(length))
00237         for val2 in val1.vertices:
00238           _x = val2
00239           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00240       length = len(self.object.poses)
00241       buff.write(_struct_I.pack(length))
00242       for val1 in self.object.poses:
00243         _v1 = val1.position
00244         _x = _v1
00245         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00246         _v2 = val1.orientation
00247         _x = _v2
00248         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00249       length = len(self.touch_links)
00250       buff.write(_struct_I.pack(length))
00251       for val1 in self.touch_links:
00252         length = len(val1)
00253         if python3 or type(val1) == unicode:
00254           val1 = val1.encode('utf-8')
00255           length = len(val1)
00256         buff.write(struct.pack('<I%ss'%length, length, val1))
00257     except struct.error as se: self._check_types(se)
00258     except TypeError as te: self._check_types(te)
00259 
00260   def deserialize(self, str):
00261     """
00262     unpack serialized message in str into this message instance
00263     :param str: byte array of serialized message, ``str``
00264     """
00265     try:
00266       if self.object is None:
00267         self.object = arm_navigation_msgs.msg.CollisionObject()
00268       end = 0
00269       start = end
00270       end += 4
00271       (length,) = _struct_I.unpack(str[start:end])
00272       start = end
00273       end += length
00274       if python3:
00275         self.link_name = str[start:end].decode('utf-8')
00276       else:
00277         self.link_name = str[start:end]
00278       _x = self
00279       start = end
00280       end += 12
00281       (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00282       start = end
00283       end += 4
00284       (length,) = _struct_I.unpack(str[start:end])
00285       start = end
00286       end += length
00287       if python3:
00288         self.object.header.frame_id = str[start:end].decode('utf-8')
00289       else:
00290         self.object.header.frame_id = str[start:end]
00291       start = end
00292       end += 4
00293       (length,) = _struct_I.unpack(str[start:end])
00294       start = end
00295       end += length
00296       if python3:
00297         self.object.id = str[start:end].decode('utf-8')
00298       else:
00299         self.object.id = str[start:end]
00300       _x = self
00301       start = end
00302       end += 5
00303       (_x.object.padding, _x.object.operation.operation,) = _struct_fb.unpack(str[start:end])
00304       start = end
00305       end += 4
00306       (length,) = _struct_I.unpack(str[start:end])
00307       self.object.shapes = []
00308       for i in range(0, length):
00309         val1 = arm_navigation_msgs.msg.Shape()
00310         start = end
00311         end += 1
00312         (val1.type,) = _struct_b.unpack(str[start:end])
00313         start = end
00314         end += 4
00315         (length,) = _struct_I.unpack(str[start:end])
00316         pattern = '<%sd'%length
00317         start = end
00318         end += struct.calcsize(pattern)
00319         val1.dimensions = struct.unpack(pattern, str[start:end])
00320         start = end
00321         end += 4
00322         (length,) = _struct_I.unpack(str[start:end])
00323         pattern = '<%si'%length
00324         start = end
00325         end += struct.calcsize(pattern)
00326         val1.triangles = struct.unpack(pattern, str[start:end])
00327         start = end
00328         end += 4
00329         (length,) = _struct_I.unpack(str[start:end])
00330         val1.vertices = []
00331         for i in range(0, length):
00332           val2 = geometry_msgs.msg.Point()
00333           _x = val2
00334           start = end
00335           end += 24
00336           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00337           val1.vertices.append(val2)
00338         self.object.shapes.append(val1)
00339       start = end
00340       end += 4
00341       (length,) = _struct_I.unpack(str[start:end])
00342       self.object.poses = []
00343       for i in range(0, length):
00344         val1 = geometry_msgs.msg.Pose()
00345         _v3 = val1.position
00346         _x = _v3
00347         start = end
00348         end += 24
00349         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00350         _v4 = val1.orientation
00351         _x = _v4
00352         start = end
00353         end += 32
00354         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00355         self.object.poses.append(val1)
00356       start = end
00357       end += 4
00358       (length,) = _struct_I.unpack(str[start:end])
00359       self.touch_links = []
00360       for i in range(0, length):
00361         start = end
00362         end += 4
00363         (length,) = _struct_I.unpack(str[start:end])
00364         start = end
00365         end += length
00366         if python3:
00367           val1 = str[start:end].decode('utf-8')
00368         else:
00369           val1 = str[start:end]
00370         self.touch_links.append(val1)
00371       return self
00372     except struct.error as e:
00373       raise genpy.DeserializationError(e) #most likely buffer underfill
00374 
00375 
00376   def serialize_numpy(self, buff, numpy):
00377     """
00378     serialize message with numpy array types into buffer
00379     :param buff: buffer, ``StringIO``
00380     :param numpy: numpy python module
00381     """
00382     try:
00383       _x = self.link_name
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       _x = self
00390       buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
00391       _x = self.object.header.frame_id
00392       length = len(_x)
00393       if python3 or type(_x) == unicode:
00394         _x = _x.encode('utf-8')
00395         length = len(_x)
00396       buff.write(struct.pack('<I%ss'%length, length, _x))
00397       _x = self.object.id
00398       length = len(_x)
00399       if python3 or type(_x) == unicode:
00400         _x = _x.encode('utf-8')
00401         length = len(_x)
00402       buff.write(struct.pack('<I%ss'%length, length, _x))
00403       _x = self
00404       buff.write(_struct_fb.pack(_x.object.padding, _x.object.operation.operation))
00405       length = len(self.object.shapes)
00406       buff.write(_struct_I.pack(length))
00407       for val1 in self.object.shapes:
00408         buff.write(_struct_b.pack(val1.type))
00409         length = len(val1.dimensions)
00410         buff.write(_struct_I.pack(length))
00411         pattern = '<%sd'%length
00412         buff.write(val1.dimensions.tostring())
00413         length = len(val1.triangles)
00414         buff.write(_struct_I.pack(length))
00415         pattern = '<%si'%length
00416         buff.write(val1.triangles.tostring())
00417         length = len(val1.vertices)
00418         buff.write(_struct_I.pack(length))
00419         for val2 in val1.vertices:
00420           _x = val2
00421           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00422       length = len(self.object.poses)
00423       buff.write(_struct_I.pack(length))
00424       for val1 in self.object.poses:
00425         _v5 = val1.position
00426         _x = _v5
00427         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00428         _v6 = val1.orientation
00429         _x = _v6
00430         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00431       length = len(self.touch_links)
00432       buff.write(_struct_I.pack(length))
00433       for val1 in self.touch_links:
00434         length = len(val1)
00435         if python3 or type(val1) == unicode:
00436           val1 = val1.encode('utf-8')
00437           length = len(val1)
00438         buff.write(struct.pack('<I%ss'%length, length, val1))
00439     except struct.error as se: self._check_types(se)
00440     except TypeError as te: self._check_types(te)
00441 
00442   def deserialize_numpy(self, str, numpy):
00443     """
00444     unpack serialized message in str into this message instance using numpy for array types
00445     :param str: byte array of serialized message, ``str``
00446     :param numpy: numpy python module
00447     """
00448     try:
00449       if self.object is None:
00450         self.object = arm_navigation_msgs.msg.CollisionObject()
00451       end = 0
00452       start = end
00453       end += 4
00454       (length,) = _struct_I.unpack(str[start:end])
00455       start = end
00456       end += length
00457       if python3:
00458         self.link_name = str[start:end].decode('utf-8')
00459       else:
00460         self.link_name = str[start:end]
00461       _x = self
00462       start = end
00463       end += 12
00464       (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00465       start = end
00466       end += 4
00467       (length,) = _struct_I.unpack(str[start:end])
00468       start = end
00469       end += length
00470       if python3:
00471         self.object.header.frame_id = str[start:end].decode('utf-8')
00472       else:
00473         self.object.header.frame_id = str[start:end]
00474       start = end
00475       end += 4
00476       (length,) = _struct_I.unpack(str[start:end])
00477       start = end
00478       end += length
00479       if python3:
00480         self.object.id = str[start:end].decode('utf-8')
00481       else:
00482         self.object.id = str[start:end]
00483       _x = self
00484       start = end
00485       end += 5
00486       (_x.object.padding, _x.object.operation.operation,) = _struct_fb.unpack(str[start:end])
00487       start = end
00488       end += 4
00489       (length,) = _struct_I.unpack(str[start:end])
00490       self.object.shapes = []
00491       for i in range(0, length):
00492         val1 = arm_navigation_msgs.msg.Shape()
00493         start = end
00494         end += 1
00495         (val1.type,) = _struct_b.unpack(str[start:end])
00496         start = end
00497         end += 4
00498         (length,) = _struct_I.unpack(str[start:end])
00499         pattern = '<%sd'%length
00500         start = end
00501         end += struct.calcsize(pattern)
00502         val1.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00503         start = end
00504         end += 4
00505         (length,) = _struct_I.unpack(str[start:end])
00506         pattern = '<%si'%length
00507         start = end
00508         end += struct.calcsize(pattern)
00509         val1.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00510         start = end
00511         end += 4
00512         (length,) = _struct_I.unpack(str[start:end])
00513         val1.vertices = []
00514         for i in range(0, length):
00515           val2 = geometry_msgs.msg.Point()
00516           _x = val2
00517           start = end
00518           end += 24
00519           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00520           val1.vertices.append(val2)
00521         self.object.shapes.append(val1)
00522       start = end
00523       end += 4
00524       (length,) = _struct_I.unpack(str[start:end])
00525       self.object.poses = []
00526       for i in range(0, length):
00527         val1 = geometry_msgs.msg.Pose()
00528         _v7 = val1.position
00529         _x = _v7
00530         start = end
00531         end += 24
00532         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00533         _v8 = val1.orientation
00534         _x = _v8
00535         start = end
00536         end += 32
00537         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00538         self.object.poses.append(val1)
00539       start = end
00540       end += 4
00541       (length,) = _struct_I.unpack(str[start:end])
00542       self.touch_links = []
00543       for i in range(0, length):
00544         start = end
00545         end += 4
00546         (length,) = _struct_I.unpack(str[start:end])
00547         start = end
00548         end += length
00549         if python3:
00550           val1 = str[start:end].decode('utf-8')
00551         else:
00552           val1 = str[start:end]
00553         self.touch_links.append(val1)
00554       return self
00555     except struct.error as e:
00556       raise genpy.DeserializationError(e) #most likely buffer underfill
00557 
00558 _struct_I = genpy.struct_I
00559 _struct_4d = struct.Struct("<4d")
00560 _struct_3I = struct.Struct("<3I")
00561 _struct_b = struct.Struct("<b")
00562 _struct_fb = struct.Struct("<fb")
00563 _struct_3d = struct.Struct("<3d")


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