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


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