00001 """autogenerated by genpy from gazebo_msgs/ContactsState.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 gazebo_msgs.msg
00009 import std_msgs.msg
00010
00011 class ContactsState(genpy.Message):
00012 _md5sum = "acbcb1601a8e525bf72509f18e6f668d"
00013 _type = "gazebo_msgs/ContactsState"
00014 _has_header = True
00015 _full_text = """Header header # stamp
00016 gazebo_msgs/ContactState[] states # array of geom pairs in contact
00017
00018 ================================================================================
00019 MSG: std_msgs/Header
00020 # Standard metadata for higher-level stamped data types.
00021 # This is generally used to communicate timestamped data
00022 # in a particular coordinate frame.
00023 #
00024 # sequence ID: consecutively increasing ID
00025 uint32 seq
00026 #Two-integer timestamp that is expressed as:
00027 # * stamp.secs: seconds (stamp_secs) since epoch
00028 # * stamp.nsecs: nanoseconds since stamp_secs
00029 # time-handling sugar is provided by the client library
00030 time stamp
00031 #Frame this data is associated with
00032 # 0: no frame
00033 # 1: global frame
00034 string frame_id
00035
00036 ================================================================================
00037 MSG: gazebo_msgs/ContactState
00038 string info # text info on this contact
00039 string collision1_name # name of contact collision1
00040 string collision2_name # name of contact collision2
00041 geometry_msgs/Wrench[] wrenches # list of forces/torques
00042 geometry_msgs/Wrench total_wrench # sum of forces/torques in every DOF
00043 geometry_msgs/Vector3[] contact_positions # list of contact position
00044 geometry_msgs/Vector3[] contact_normals # list of contact normals
00045 float64[] depths # list of penetration depths
00046
00047 ================================================================================
00048 MSG: geometry_msgs/Wrench
00049 # This represents force in free space, separated into
00050 # its linear and angular parts.
00051 Vector3 force
00052 Vector3 torque
00053
00054 ================================================================================
00055 MSG: geometry_msgs/Vector3
00056 # This represents a vector in free space.
00057
00058 float64 x
00059 float64 y
00060 float64 z
00061 """
00062 __slots__ = ['header','states']
00063 _slot_types = ['std_msgs/Header','gazebo_msgs/ContactState[]']
00064
00065 def __init__(self, *args, **kwds):
00066 """
00067 Constructor. Any message fields that are implicitly/explicitly
00068 set to None will be assigned a default value. The recommend
00069 use is keyword arguments as this is more robust to future message
00070 changes. You cannot mix in-order arguments and keyword arguments.
00071
00072 The available fields are:
00073 header,states
00074
00075 :param args: complete set of field values, in .msg order
00076 :param kwds: use keyword arguments corresponding to message field names
00077 to set specific fields.
00078 """
00079 if args or kwds:
00080 super(ContactsState, self).__init__(*args, **kwds)
00081
00082 if self.header is None:
00083 self.header = std_msgs.msg.Header()
00084 if self.states is None:
00085 self.states = []
00086 else:
00087 self.header = std_msgs.msg.Header()
00088 self.states = []
00089
00090 def _get_types(self):
00091 """
00092 internal API method
00093 """
00094 return self._slot_types
00095
00096 def serialize(self, buff):
00097 """
00098 serialize message into buffer
00099 :param buff: buffer, ``StringIO``
00100 """
00101 try:
00102 _x = self
00103 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00104 _x = self.header.frame_id
00105 length = len(_x)
00106 if python3 or type(_x) == unicode:
00107 _x = _x.encode('utf-8')
00108 length = len(_x)
00109 buff.write(struct.pack('<I%ss'%length, length, _x))
00110 length = len(self.states)
00111 buff.write(_struct_I.pack(length))
00112 for val1 in self.states:
00113 _x = val1.info
00114 length = len(_x)
00115 if python3 or type(_x) == unicode:
00116 _x = _x.encode('utf-8')
00117 length = len(_x)
00118 buff.write(struct.pack('<I%ss'%length, length, _x))
00119 _x = val1.collision1_name
00120 length = len(_x)
00121 if python3 or type(_x) == unicode:
00122 _x = _x.encode('utf-8')
00123 length = len(_x)
00124 buff.write(struct.pack('<I%ss'%length, length, _x))
00125 _x = val1.collision2_name
00126 length = len(_x)
00127 if python3 or type(_x) == unicode:
00128 _x = _x.encode('utf-8')
00129 length = len(_x)
00130 buff.write(struct.pack('<I%ss'%length, length, _x))
00131 length = len(val1.wrenches)
00132 buff.write(_struct_I.pack(length))
00133 for val2 in val1.wrenches:
00134 _v1 = val2.force
00135 _x = _v1
00136 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00137 _v2 = val2.torque
00138 _x = _v2
00139 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00140 _v3 = val1.total_wrench
00141 _v4 = _v3.force
00142 _x = _v4
00143 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00144 _v5 = _v3.torque
00145 _x = _v5
00146 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00147 length = len(val1.contact_positions)
00148 buff.write(_struct_I.pack(length))
00149 for val2 in val1.contact_positions:
00150 _x = val2
00151 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00152 length = len(val1.contact_normals)
00153 buff.write(_struct_I.pack(length))
00154 for val2 in val1.contact_normals:
00155 _x = val2
00156 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00157 length = len(val1.depths)
00158 buff.write(_struct_I.pack(length))
00159 pattern = '<%sd'%length
00160 buff.write(struct.pack(pattern, *val1.depths))
00161 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00162 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00163
00164 def deserialize(self, str):
00165 """
00166 unpack serialized message in str into this message instance
00167 :param str: byte array of serialized message, ``str``
00168 """
00169 try:
00170 if self.header is None:
00171 self.header = std_msgs.msg.Header()
00172 if self.states is None:
00173 self.states = None
00174 end = 0
00175 _x = self
00176 start = end
00177 end += 12
00178 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00179 start = end
00180 end += 4
00181 (length,) = _struct_I.unpack(str[start:end])
00182 start = end
00183 end += length
00184 if python3:
00185 self.header.frame_id = str[start:end].decode('utf-8')
00186 else:
00187 self.header.frame_id = str[start:end]
00188 start = end
00189 end += 4
00190 (length,) = _struct_I.unpack(str[start:end])
00191 self.states = []
00192 for i in range(0, length):
00193 val1 = gazebo_msgs.msg.ContactState()
00194 start = end
00195 end += 4
00196 (length,) = _struct_I.unpack(str[start:end])
00197 start = end
00198 end += length
00199 if python3:
00200 val1.info = str[start:end].decode('utf-8')
00201 else:
00202 val1.info = str[start:end]
00203 start = end
00204 end += 4
00205 (length,) = _struct_I.unpack(str[start:end])
00206 start = end
00207 end += length
00208 if python3:
00209 val1.collision1_name = str[start:end].decode('utf-8')
00210 else:
00211 val1.collision1_name = str[start:end]
00212 start = end
00213 end += 4
00214 (length,) = _struct_I.unpack(str[start:end])
00215 start = end
00216 end += length
00217 if python3:
00218 val1.collision2_name = str[start:end].decode('utf-8')
00219 else:
00220 val1.collision2_name = str[start:end]
00221 start = end
00222 end += 4
00223 (length,) = _struct_I.unpack(str[start:end])
00224 val1.wrenches = []
00225 for i in range(0, length):
00226 val2 = geometry_msgs.msg.Wrench()
00227 _v6 = val2.force
00228 _x = _v6
00229 start = end
00230 end += 24
00231 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00232 _v7 = val2.torque
00233 _x = _v7
00234 start = end
00235 end += 24
00236 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00237 val1.wrenches.append(val2)
00238 _v8 = val1.total_wrench
00239 _v9 = _v8.force
00240 _x = _v9
00241 start = end
00242 end += 24
00243 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00244 _v10 = _v8.torque
00245 _x = _v10
00246 start = end
00247 end += 24
00248 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00249 start = end
00250 end += 4
00251 (length,) = _struct_I.unpack(str[start:end])
00252 val1.contact_positions = []
00253 for i in range(0, length):
00254 val2 = geometry_msgs.msg.Vector3()
00255 _x = val2
00256 start = end
00257 end += 24
00258 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00259 val1.contact_positions.append(val2)
00260 start = end
00261 end += 4
00262 (length,) = _struct_I.unpack(str[start:end])
00263 val1.contact_normals = []
00264 for i in range(0, length):
00265 val2 = geometry_msgs.msg.Vector3()
00266 _x = val2
00267 start = end
00268 end += 24
00269 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00270 val1.contact_normals.append(val2)
00271 start = end
00272 end += 4
00273 (length,) = _struct_I.unpack(str[start:end])
00274 pattern = '<%sd'%length
00275 start = end
00276 end += struct.calcsize(pattern)
00277 val1.depths = struct.unpack(pattern, str[start:end])
00278 self.states.append(val1)
00279 return self
00280 except struct.error as e:
00281 raise genpy.DeserializationError(e)
00282
00283
00284 def serialize_numpy(self, buff, numpy):
00285 """
00286 serialize message with numpy array types into buffer
00287 :param buff: buffer, ``StringIO``
00288 :param numpy: numpy python module
00289 """
00290 try:
00291 _x = self
00292 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00293 _x = self.header.frame_id
00294 length = len(_x)
00295 if python3 or type(_x) == unicode:
00296 _x = _x.encode('utf-8')
00297 length = len(_x)
00298 buff.write(struct.pack('<I%ss'%length, length, _x))
00299 length = len(self.states)
00300 buff.write(_struct_I.pack(length))
00301 for val1 in self.states:
00302 _x = val1.info
00303 length = len(_x)
00304 if python3 or type(_x) == unicode:
00305 _x = _x.encode('utf-8')
00306 length = len(_x)
00307 buff.write(struct.pack('<I%ss'%length, length, _x))
00308 _x = val1.collision1_name
00309 length = len(_x)
00310 if python3 or type(_x) == unicode:
00311 _x = _x.encode('utf-8')
00312 length = len(_x)
00313 buff.write(struct.pack('<I%ss'%length, length, _x))
00314 _x = val1.collision2_name
00315 length = len(_x)
00316 if python3 or type(_x) == unicode:
00317 _x = _x.encode('utf-8')
00318 length = len(_x)
00319 buff.write(struct.pack('<I%ss'%length, length, _x))
00320 length = len(val1.wrenches)
00321 buff.write(_struct_I.pack(length))
00322 for val2 in val1.wrenches:
00323 _v11 = val2.force
00324 _x = _v11
00325 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00326 _v12 = val2.torque
00327 _x = _v12
00328 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00329 _v13 = val1.total_wrench
00330 _v14 = _v13.force
00331 _x = _v14
00332 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00333 _v15 = _v13.torque
00334 _x = _v15
00335 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00336 length = len(val1.contact_positions)
00337 buff.write(_struct_I.pack(length))
00338 for val2 in val1.contact_positions:
00339 _x = val2
00340 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00341 length = len(val1.contact_normals)
00342 buff.write(_struct_I.pack(length))
00343 for val2 in val1.contact_normals:
00344 _x = val2
00345 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00346 length = len(val1.depths)
00347 buff.write(_struct_I.pack(length))
00348 pattern = '<%sd'%length
00349 buff.write(val1.depths.tostring())
00350 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00351 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00352
00353 def deserialize_numpy(self, str, numpy):
00354 """
00355 unpack serialized message in str into this message instance using numpy for array types
00356 :param str: byte array of serialized message, ``str``
00357 :param numpy: numpy python module
00358 """
00359 try:
00360 if self.header is None:
00361 self.header = std_msgs.msg.Header()
00362 if self.states is None:
00363 self.states = None
00364 end = 0
00365 _x = self
00366 start = end
00367 end += 12
00368 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 start = end
00373 end += length
00374 if python3:
00375 self.header.frame_id = str[start:end].decode('utf-8')
00376 else:
00377 self.header.frame_id = str[start:end]
00378 start = end
00379 end += 4
00380 (length,) = _struct_I.unpack(str[start:end])
00381 self.states = []
00382 for i in range(0, length):
00383 val1 = gazebo_msgs.msg.ContactState()
00384 start = end
00385 end += 4
00386 (length,) = _struct_I.unpack(str[start:end])
00387 start = end
00388 end += length
00389 if python3:
00390 val1.info = str[start:end].decode('utf-8')
00391 else:
00392 val1.info = str[start:end]
00393 start = end
00394 end += 4
00395 (length,) = _struct_I.unpack(str[start:end])
00396 start = end
00397 end += length
00398 if python3:
00399 val1.collision1_name = str[start:end].decode('utf-8')
00400 else:
00401 val1.collision1_name = 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 val1.collision2_name = str[start:end].decode('utf-8')
00409 else:
00410 val1.collision2_name = str[start:end]
00411 start = end
00412 end += 4
00413 (length,) = _struct_I.unpack(str[start:end])
00414 val1.wrenches = []
00415 for i in range(0, length):
00416 val2 = geometry_msgs.msg.Wrench()
00417 _v16 = val2.force
00418 _x = _v16
00419 start = end
00420 end += 24
00421 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00422 _v17 = val2.torque
00423 _x = _v17
00424 start = end
00425 end += 24
00426 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00427 val1.wrenches.append(val2)
00428 _v18 = val1.total_wrench
00429 _v19 = _v18.force
00430 _x = _v19
00431 start = end
00432 end += 24
00433 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00434 _v20 = _v18.torque
00435 _x = _v20
00436 start = end
00437 end += 24
00438 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00439 start = end
00440 end += 4
00441 (length,) = _struct_I.unpack(str[start:end])
00442 val1.contact_positions = []
00443 for i in range(0, length):
00444 val2 = geometry_msgs.msg.Vector3()
00445 _x = val2
00446 start = end
00447 end += 24
00448 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00449 val1.contact_positions.append(val2)
00450 start = end
00451 end += 4
00452 (length,) = _struct_I.unpack(str[start:end])
00453 val1.contact_normals = []
00454 for i in range(0, length):
00455 val2 = geometry_msgs.msg.Vector3()
00456 _x = val2
00457 start = end
00458 end += 24
00459 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00460 val1.contact_normals.append(val2)
00461 start = end
00462 end += 4
00463 (length,) = _struct_I.unpack(str[start:end])
00464 pattern = '<%sd'%length
00465 start = end
00466 end += struct.calcsize(pattern)
00467 val1.depths = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00468 self.states.append(val1)
00469 return self
00470 except struct.error as e:
00471 raise genpy.DeserializationError(e)
00472
00473 _struct_I = genpy.struct_I
00474 _struct_3I = struct.Struct("<3I")
00475 _struct_3d = struct.Struct("<3d")