_ContactState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from gazebo_msgs/ContactState.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 
00009 class ContactState(genpy.Message):
00010   _md5sum = "48c0ffb054b8c444f870cecea1ee50d9"
00011   _type = "gazebo_msgs/ContactState"
00012   _has_header = False #flag to mark the presence of a Header object
00013   _full_text = """string info                                   # text info on this contact
00014 string collision1_name                        # name of contact collision1
00015 string collision2_name                        # name of contact collision2
00016 geometry_msgs/Wrench[] wrenches               # list of forces/torques
00017 geometry_msgs/Wrench total_wrench             # sum of forces/torques in every DOF
00018 geometry_msgs/Vector3[] contact_positions     # list of contact position
00019 geometry_msgs/Vector3[] contact_normals       # list of contact normals
00020 float64[] depths                              # list of penetration depths
00021 
00022 ================================================================================
00023 MSG: geometry_msgs/Wrench
00024 # This represents force in free space, separated into
00025 # its linear and angular parts.
00026 Vector3  force
00027 Vector3  torque
00028 
00029 ================================================================================
00030 MSG: geometry_msgs/Vector3
00031 # This represents a vector in free space. 
00032 
00033 float64 x
00034 float64 y
00035 float64 z
00036 """
00037   __slots__ = ['info','collision1_name','collision2_name','wrenches','total_wrench','contact_positions','contact_normals','depths']
00038   _slot_types = ['string','string','string','geometry_msgs/Wrench[]','geometry_msgs/Wrench','geometry_msgs/Vector3[]','geometry_msgs/Vector3[]','float64[]']
00039 
00040   def __init__(self, *args, **kwds):
00041     """
00042     Constructor. Any message fields that are implicitly/explicitly
00043     set to None will be assigned a default value. The recommend
00044     use is keyword arguments as this is more robust to future message
00045     changes.  You cannot mix in-order arguments and keyword arguments.
00046 
00047     The available fields are:
00048        info,collision1_name,collision2_name,wrenches,total_wrench,contact_positions,contact_normals,depths
00049 
00050     :param args: complete set of field values, in .msg order
00051     :param kwds: use keyword arguments corresponding to message field names
00052     to set specific fields.
00053     """
00054     if args or kwds:
00055       super(ContactState, self).__init__(*args, **kwds)
00056       #message fields cannot be None, assign default values for those that are
00057       if self.info is None:
00058         self.info = ''
00059       if self.collision1_name is None:
00060         self.collision1_name = ''
00061       if self.collision2_name is None:
00062         self.collision2_name = ''
00063       if self.wrenches is None:
00064         self.wrenches = []
00065       if self.total_wrench is None:
00066         self.total_wrench = geometry_msgs.msg.Wrench()
00067       if self.contact_positions is None:
00068         self.contact_positions = []
00069       if self.contact_normals is None:
00070         self.contact_normals = []
00071       if self.depths is None:
00072         self.depths = []
00073     else:
00074       self.info = ''
00075       self.collision1_name = ''
00076       self.collision2_name = ''
00077       self.wrenches = []
00078       self.total_wrench = geometry_msgs.msg.Wrench()
00079       self.contact_positions = []
00080       self.contact_normals = []
00081       self.depths = []
00082 
00083   def _get_types(self):
00084     """
00085     internal API method
00086     """
00087     return self._slot_types
00088 
00089   def serialize(self, buff):
00090     """
00091     serialize message into buffer
00092     :param buff: buffer, ``StringIO``
00093     """
00094     try:
00095       _x = self.info
00096       length = len(_x)
00097       if python3 or type(_x) == unicode:
00098         _x = _x.encode('utf-8')
00099         length = len(_x)
00100       buff.write(struct.pack('<I%ss'%length, length, _x))
00101       _x = self.collision1_name
00102       length = len(_x)
00103       if python3 or type(_x) == unicode:
00104         _x = _x.encode('utf-8')
00105         length = len(_x)
00106       buff.write(struct.pack('<I%ss'%length, length, _x))
00107       _x = self.collision2_name
00108       length = len(_x)
00109       if python3 or type(_x) == unicode:
00110         _x = _x.encode('utf-8')
00111         length = len(_x)
00112       buff.write(struct.pack('<I%ss'%length, length, _x))
00113       length = len(self.wrenches)
00114       buff.write(_struct_I.pack(length))
00115       for val1 in self.wrenches:
00116         _v1 = val1.force
00117         _x = _v1
00118         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00119         _v2 = val1.torque
00120         _x = _v2
00121         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00122       _x = self
00123       buff.write(_struct_6d.pack(_x.total_wrench.force.x, _x.total_wrench.force.y, _x.total_wrench.force.z, _x.total_wrench.torque.x, _x.total_wrench.torque.y, _x.total_wrench.torque.z))
00124       length = len(self.contact_positions)
00125       buff.write(_struct_I.pack(length))
00126       for val1 in self.contact_positions:
00127         _x = val1
00128         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00129       length = len(self.contact_normals)
00130       buff.write(_struct_I.pack(length))
00131       for val1 in self.contact_normals:
00132         _x = val1
00133         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00134       length = len(self.depths)
00135       buff.write(_struct_I.pack(length))
00136       pattern = '<%sd'%length
00137       buff.write(struct.pack(pattern, *self.depths))
00138     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00139     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00140 
00141   def deserialize(self, str):
00142     """
00143     unpack serialized message in str into this message instance
00144     :param str: byte array of serialized message, ``str``
00145     """
00146     try:
00147       if self.wrenches is None:
00148         self.wrenches = None
00149       if self.total_wrench is None:
00150         self.total_wrench = geometry_msgs.msg.Wrench()
00151       if self.contact_positions is None:
00152         self.contact_positions = None
00153       if self.contact_normals is None:
00154         self.contact_normals = None
00155       end = 0
00156       start = end
00157       end += 4
00158       (length,) = _struct_I.unpack(str[start:end])
00159       start = end
00160       end += length
00161       if python3:
00162         self.info = str[start:end].decode('utf-8')
00163       else:
00164         self.info = str[start:end]
00165       start = end
00166       end += 4
00167       (length,) = _struct_I.unpack(str[start:end])
00168       start = end
00169       end += length
00170       if python3:
00171         self.collision1_name = str[start:end].decode('utf-8')
00172       else:
00173         self.collision1_name = str[start:end]
00174       start = end
00175       end += 4
00176       (length,) = _struct_I.unpack(str[start:end])
00177       start = end
00178       end += length
00179       if python3:
00180         self.collision2_name = str[start:end].decode('utf-8')
00181       else:
00182         self.collision2_name = str[start:end]
00183       start = end
00184       end += 4
00185       (length,) = _struct_I.unpack(str[start:end])
00186       self.wrenches = []
00187       for i in range(0, length):
00188         val1 = geometry_msgs.msg.Wrench()
00189         _v3 = val1.force
00190         _x = _v3
00191         start = end
00192         end += 24
00193         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00194         _v4 = val1.torque
00195         _x = _v4
00196         start = end
00197         end += 24
00198         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00199         self.wrenches.append(val1)
00200       _x = self
00201       start = end
00202       end += 48
00203       (_x.total_wrench.force.x, _x.total_wrench.force.y, _x.total_wrench.force.z, _x.total_wrench.torque.x, _x.total_wrench.torque.y, _x.total_wrench.torque.z,) = _struct_6d.unpack(str[start:end])
00204       start = end
00205       end += 4
00206       (length,) = _struct_I.unpack(str[start:end])
00207       self.contact_positions = []
00208       for i in range(0, length):
00209         val1 = geometry_msgs.msg.Vector3()
00210         _x = val1
00211         start = end
00212         end += 24
00213         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00214         self.contact_positions.append(val1)
00215       start = end
00216       end += 4
00217       (length,) = _struct_I.unpack(str[start:end])
00218       self.contact_normals = []
00219       for i in range(0, length):
00220         val1 = geometry_msgs.msg.Vector3()
00221         _x = val1
00222         start = end
00223         end += 24
00224         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00225         self.contact_normals.append(val1)
00226       start = end
00227       end += 4
00228       (length,) = _struct_I.unpack(str[start:end])
00229       pattern = '<%sd'%length
00230       start = end
00231       end += struct.calcsize(pattern)
00232       self.depths = struct.unpack(pattern, str[start:end])
00233       return self
00234     except struct.error as e:
00235       raise genpy.DeserializationError(e) #most likely buffer underfill
00236 
00237 
00238   def serialize_numpy(self, buff, numpy):
00239     """
00240     serialize message with numpy array types into buffer
00241     :param buff: buffer, ``StringIO``
00242     :param numpy: numpy python module
00243     """
00244     try:
00245       _x = self.info
00246       length = len(_x)
00247       if python3 or type(_x) == unicode:
00248         _x = _x.encode('utf-8')
00249         length = len(_x)
00250       buff.write(struct.pack('<I%ss'%length, length, _x))
00251       _x = self.collision1_name
00252       length = len(_x)
00253       if python3 or type(_x) == unicode:
00254         _x = _x.encode('utf-8')
00255         length = len(_x)
00256       buff.write(struct.pack('<I%ss'%length, length, _x))
00257       _x = self.collision2_name
00258       length = len(_x)
00259       if python3 or type(_x) == unicode:
00260         _x = _x.encode('utf-8')
00261         length = len(_x)
00262       buff.write(struct.pack('<I%ss'%length, length, _x))
00263       length = len(self.wrenches)
00264       buff.write(_struct_I.pack(length))
00265       for val1 in self.wrenches:
00266         _v5 = val1.force
00267         _x = _v5
00268         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00269         _v6 = val1.torque
00270         _x = _v6
00271         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00272       _x = self
00273       buff.write(_struct_6d.pack(_x.total_wrench.force.x, _x.total_wrench.force.y, _x.total_wrench.force.z, _x.total_wrench.torque.x, _x.total_wrench.torque.y, _x.total_wrench.torque.z))
00274       length = len(self.contact_positions)
00275       buff.write(_struct_I.pack(length))
00276       for val1 in self.contact_positions:
00277         _x = val1
00278         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00279       length = len(self.contact_normals)
00280       buff.write(_struct_I.pack(length))
00281       for val1 in self.contact_normals:
00282         _x = val1
00283         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00284       length = len(self.depths)
00285       buff.write(_struct_I.pack(length))
00286       pattern = '<%sd'%length
00287       buff.write(self.depths.tostring())
00288     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00289     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00290 
00291   def deserialize_numpy(self, str, numpy):
00292     """
00293     unpack serialized message in str into this message instance using numpy for array types
00294     :param str: byte array of serialized message, ``str``
00295     :param numpy: numpy python module
00296     """
00297     try:
00298       if self.wrenches is None:
00299         self.wrenches = None
00300       if self.total_wrench is None:
00301         self.total_wrench = geometry_msgs.msg.Wrench()
00302       if self.contact_positions is None:
00303         self.contact_positions = None
00304       if self.contact_normals is None:
00305         self.contact_normals = None
00306       end = 0
00307       start = end
00308       end += 4
00309       (length,) = _struct_I.unpack(str[start:end])
00310       start = end
00311       end += length
00312       if python3:
00313         self.info = str[start:end].decode('utf-8')
00314       else:
00315         self.info = str[start:end]
00316       start = end
00317       end += 4
00318       (length,) = _struct_I.unpack(str[start:end])
00319       start = end
00320       end += length
00321       if python3:
00322         self.collision1_name = str[start:end].decode('utf-8')
00323       else:
00324         self.collision1_name = str[start:end]
00325       start = end
00326       end += 4
00327       (length,) = _struct_I.unpack(str[start:end])
00328       start = end
00329       end += length
00330       if python3:
00331         self.collision2_name = str[start:end].decode('utf-8')
00332       else:
00333         self.collision2_name = str[start:end]
00334       start = end
00335       end += 4
00336       (length,) = _struct_I.unpack(str[start:end])
00337       self.wrenches = []
00338       for i in range(0, length):
00339         val1 = geometry_msgs.msg.Wrench()
00340         _v7 = val1.force
00341         _x = _v7
00342         start = end
00343         end += 24
00344         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00345         _v8 = val1.torque
00346         _x = _v8
00347         start = end
00348         end += 24
00349         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00350         self.wrenches.append(val1)
00351       _x = self
00352       start = end
00353       end += 48
00354       (_x.total_wrench.force.x, _x.total_wrench.force.y, _x.total_wrench.force.z, _x.total_wrench.torque.x, _x.total_wrench.torque.y, _x.total_wrench.torque.z,) = _struct_6d.unpack(str[start:end])
00355       start = end
00356       end += 4
00357       (length,) = _struct_I.unpack(str[start:end])
00358       self.contact_positions = []
00359       for i in range(0, length):
00360         val1 = geometry_msgs.msg.Vector3()
00361         _x = val1
00362         start = end
00363         end += 24
00364         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00365         self.contact_positions.append(val1)
00366       start = end
00367       end += 4
00368       (length,) = _struct_I.unpack(str[start:end])
00369       self.contact_normals = []
00370       for i in range(0, length):
00371         val1 = geometry_msgs.msg.Vector3()
00372         _x = val1
00373         start = end
00374         end += 24
00375         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00376         self.contact_normals.append(val1)
00377       start = end
00378       end += 4
00379       (length,) = _struct_I.unpack(str[start:end])
00380       pattern = '<%sd'%length
00381       start = end
00382       end += struct.calcsize(pattern)
00383       self.depths = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00384       return self
00385     except struct.error as e:
00386       raise genpy.DeserializationError(e) #most likely buffer underfill
00387 
00388 _struct_I = genpy.struct_I
00389 _struct_6d = struct.Struct("<6d")
00390 _struct_3d = struct.Struct("<3d")


gazebo_msgs
Author(s): John Hsu
autogenerated on Mon Oct 6 2014 12:14:33