_WorldState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from gazebo_msgs/WorldState.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 std_msgs.msg
00009 
00010 class WorldState(genpy.Message):
00011   _md5sum = "de1a9de3ab7ba97ac0e9ec01a4eb481e"
00012   _type = "gazebo_msgs/WorldState"
00013   _has_header = True #flag to mark the presence of a Header object
00014   _full_text = """# This is a message that holds data necessary to reconstruct a snapshot of the world
00015 #
00016 # = Approach to Message Passing =
00017 # The state of the world is defined by either
00018 #   1. Inertial Model pose, twist
00019 #      * kinematic data - connectivity graph from Model to each Link
00020 #      * joint angles
00021 #      * joint velocities
00022 #      * Applied forces - Body wrench
00023 #        * relative transform from Body to each collision Geom
00024 # Or
00025 #   2. Inertial (absolute) Body pose, twist, wrench
00026 #      * relative transform from Body to each collision Geom - constant, so not sent over wire
00027 #      * back compute from canonical body info to get Model pose and twist.
00028 #
00029 # Chooing (2.) because it matches most physics engines out there
00030 #   and is simpler.
00031 #
00032 # = Future =
00033 # Consider impacts on using reduced coordinates / graph (parent/child links) approach
00034 #   constraint and physics solvers.
00035 #
00036 # = Application =
00037 # This message is used to do the following:
00038 #   * reconstruct the world and objects for sensor generation
00039 #   * stop / start simulation - need pose, twist, wrench of each body
00040 #   * collision detection - need pose of each collision geometry.  velocity/acceleration if 
00041 #
00042 # = Assumptions =
00043 # Assuming that each (physics) processor node locally already has
00044 #   * collision information - Trimesh for Geoms, etc
00045 #   * relative transforms from Body to Geom - this is assumed to be fixed, do not send oved wire
00046 #   * inertial information - does not vary in time
00047 #   * visual information - does not vary in time
00048 #
00049 
00050 Header header
00051 
00052 string[] name
00053 geometry_msgs/Pose[] pose
00054 geometry_msgs/Twist[] twist
00055 geometry_msgs/Wrench[] wrench
00056 
00057 ================================================================================
00058 MSG: std_msgs/Header
00059 # Standard metadata for higher-level stamped data types.
00060 # This is generally used to communicate timestamped data 
00061 # in a particular coordinate frame.
00062 # 
00063 # sequence ID: consecutively increasing ID 
00064 uint32 seq
00065 #Two-integer timestamp that is expressed as:
00066 # * stamp.secs: seconds (stamp_secs) since epoch
00067 # * stamp.nsecs: nanoseconds since stamp_secs
00068 # time-handling sugar is provided by the client library
00069 time stamp
00070 #Frame this data is associated with
00071 # 0: no frame
00072 # 1: global frame
00073 string frame_id
00074 
00075 ================================================================================
00076 MSG: geometry_msgs/Pose
00077 # A representation of pose in free space, composed of postion and orientation. 
00078 Point position
00079 Quaternion orientation
00080 
00081 ================================================================================
00082 MSG: geometry_msgs/Point
00083 # This contains the position of a point in free space
00084 float64 x
00085 float64 y
00086 float64 z
00087 
00088 ================================================================================
00089 MSG: geometry_msgs/Quaternion
00090 # This represents an orientation in free space in quaternion form.
00091 
00092 float64 x
00093 float64 y
00094 float64 z
00095 float64 w
00096 
00097 ================================================================================
00098 MSG: geometry_msgs/Twist
00099 # This expresses velocity in free space broken into its linear and angular parts.
00100 Vector3  linear
00101 Vector3  angular
00102 
00103 ================================================================================
00104 MSG: geometry_msgs/Vector3
00105 # This represents a vector in free space. 
00106 
00107 float64 x
00108 float64 y
00109 float64 z
00110 ================================================================================
00111 MSG: geometry_msgs/Wrench
00112 # This represents force in free space, separated into
00113 # its linear and angular parts.
00114 Vector3  force
00115 Vector3  torque
00116 
00117 """
00118   __slots__ = ['header','name','pose','twist','wrench']
00119   _slot_types = ['std_msgs/Header','string[]','geometry_msgs/Pose[]','geometry_msgs/Twist[]','geometry_msgs/Wrench[]']
00120 
00121   def __init__(self, *args, **kwds):
00122     """
00123     Constructor. Any message fields that are implicitly/explicitly
00124     set to None will be assigned a default value. The recommend
00125     use is keyword arguments as this is more robust to future message
00126     changes.  You cannot mix in-order arguments and keyword arguments.
00127 
00128     The available fields are:
00129        header,name,pose,twist,wrench
00130 
00131     :param args: complete set of field values, in .msg order
00132     :param kwds: use keyword arguments corresponding to message field names
00133     to set specific fields.
00134     """
00135     if args or kwds:
00136       super(WorldState, self).__init__(*args, **kwds)
00137       #message fields cannot be None, assign default values for those that are
00138       if self.header is None:
00139         self.header = std_msgs.msg.Header()
00140       if self.name is None:
00141         self.name = []
00142       if self.pose is None:
00143         self.pose = []
00144       if self.twist is None:
00145         self.twist = []
00146       if self.wrench is None:
00147         self.wrench = []
00148     else:
00149       self.header = std_msgs.msg.Header()
00150       self.name = []
00151       self.pose = []
00152       self.twist = []
00153       self.wrench = []
00154 
00155   def _get_types(self):
00156     """
00157     internal API method
00158     """
00159     return self._slot_types
00160 
00161   def serialize(self, buff):
00162     """
00163     serialize message into buffer
00164     :param buff: buffer, ``StringIO``
00165     """
00166     try:
00167       _x = self
00168       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00169       _x = self.header.frame_id
00170       length = len(_x)
00171       if python3 or type(_x) == unicode:
00172         _x = _x.encode('utf-8')
00173         length = len(_x)
00174       buff.write(struct.pack('<I%ss'%length, length, _x))
00175       length = len(self.name)
00176       buff.write(_struct_I.pack(length))
00177       for val1 in self.name:
00178         length = len(val1)
00179         if python3 or type(val1) == unicode:
00180           val1 = val1.encode('utf-8')
00181           length = len(val1)
00182         buff.write(struct.pack('<I%ss'%length, length, val1))
00183       length = len(self.pose)
00184       buff.write(_struct_I.pack(length))
00185       for val1 in self.pose:
00186         _v1 = val1.position
00187         _x = _v1
00188         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00189         _v2 = val1.orientation
00190         _x = _v2
00191         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00192       length = len(self.twist)
00193       buff.write(_struct_I.pack(length))
00194       for val1 in self.twist:
00195         _v3 = val1.linear
00196         _x = _v3
00197         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00198         _v4 = val1.angular
00199         _x = _v4
00200         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00201       length = len(self.wrench)
00202       buff.write(_struct_I.pack(length))
00203       for val1 in self.wrench:
00204         _v5 = val1.force
00205         _x = _v5
00206         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00207         _v6 = val1.torque
00208         _x = _v6
00209         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00210     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00211     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00212 
00213   def deserialize(self, str):
00214     """
00215     unpack serialized message in str into this message instance
00216     :param str: byte array of serialized message, ``str``
00217     """
00218     try:
00219       if self.header is None:
00220         self.header = std_msgs.msg.Header()
00221       if self.pose is None:
00222         self.pose = None
00223       if self.twist is None:
00224         self.twist = None
00225       if self.wrench is None:
00226         self.wrench = None
00227       end = 0
00228       _x = self
00229       start = end
00230       end += 12
00231       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00232       start = end
00233       end += 4
00234       (length,) = _struct_I.unpack(str[start:end])
00235       start = end
00236       end += length
00237       if python3:
00238         self.header.frame_id = str[start:end].decode('utf-8')
00239       else:
00240         self.header.frame_id = str[start:end]
00241       start = end
00242       end += 4
00243       (length,) = _struct_I.unpack(str[start:end])
00244       self.name = []
00245       for i in range(0, length):
00246         start = end
00247         end += 4
00248         (length,) = _struct_I.unpack(str[start:end])
00249         start = end
00250         end += length
00251         if python3:
00252           val1 = str[start:end].decode('utf-8')
00253         else:
00254           val1 = str[start:end]
00255         self.name.append(val1)
00256       start = end
00257       end += 4
00258       (length,) = _struct_I.unpack(str[start:end])
00259       self.pose = []
00260       for i in range(0, length):
00261         val1 = geometry_msgs.msg.Pose()
00262         _v7 = val1.position
00263         _x = _v7
00264         start = end
00265         end += 24
00266         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00267         _v8 = val1.orientation
00268         _x = _v8
00269         start = end
00270         end += 32
00271         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00272         self.pose.append(val1)
00273       start = end
00274       end += 4
00275       (length,) = _struct_I.unpack(str[start:end])
00276       self.twist = []
00277       for i in range(0, length):
00278         val1 = geometry_msgs.msg.Twist()
00279         _v9 = val1.linear
00280         _x = _v9
00281         start = end
00282         end += 24
00283         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00284         _v10 = val1.angular
00285         _x = _v10
00286         start = end
00287         end += 24
00288         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00289         self.twist.append(val1)
00290       start = end
00291       end += 4
00292       (length,) = _struct_I.unpack(str[start:end])
00293       self.wrench = []
00294       for i in range(0, length):
00295         val1 = geometry_msgs.msg.Wrench()
00296         _v11 = val1.force
00297         _x = _v11
00298         start = end
00299         end += 24
00300         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00301         _v12 = val1.torque
00302         _x = _v12
00303         start = end
00304         end += 24
00305         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00306         self.wrench.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_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00321       _x = self.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       length = len(self.name)
00328       buff.write(_struct_I.pack(length))
00329       for val1 in self.name:
00330         length = len(val1)
00331         if python3 or type(val1) == unicode:
00332           val1 = val1.encode('utf-8')
00333           length = len(val1)
00334         buff.write(struct.pack('<I%ss'%length, length, val1))
00335       length = len(self.pose)
00336       buff.write(_struct_I.pack(length))
00337       for val1 in self.pose:
00338         _v13 = val1.position
00339         _x = _v13
00340         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00341         _v14 = val1.orientation
00342         _x = _v14
00343         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00344       length = len(self.twist)
00345       buff.write(_struct_I.pack(length))
00346       for val1 in self.twist:
00347         _v15 = val1.linear
00348         _x = _v15
00349         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00350         _v16 = val1.angular
00351         _x = _v16
00352         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00353       length = len(self.wrench)
00354       buff.write(_struct_I.pack(length))
00355       for val1 in self.wrench:
00356         _v17 = val1.force
00357         _x = _v17
00358         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00359         _v18 = val1.torque
00360         _x = _v18
00361         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00362     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00363     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00364 
00365   def deserialize_numpy(self, str, numpy):
00366     """
00367     unpack serialized message in str into this message instance using numpy for array types
00368     :param str: byte array of serialized message, ``str``
00369     :param numpy: numpy python module
00370     """
00371     try:
00372       if self.header is None:
00373         self.header = std_msgs.msg.Header()
00374       if self.pose is None:
00375         self.pose = None
00376       if self.twist is None:
00377         self.twist = None
00378       if self.wrench is None:
00379         self.wrench = None
00380       end = 0
00381       _x = self
00382       start = end
00383       end += 12
00384       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00385       start = end
00386       end += 4
00387       (length,) = _struct_I.unpack(str[start:end])
00388       start = end
00389       end += length
00390       if python3:
00391         self.header.frame_id = str[start:end].decode('utf-8')
00392       else:
00393         self.header.frame_id = str[start:end]
00394       start = end
00395       end += 4
00396       (length,) = _struct_I.unpack(str[start:end])
00397       self.name = []
00398       for i in range(0, length):
00399         start = end
00400         end += 4
00401         (length,) = _struct_I.unpack(str[start:end])
00402         start = end
00403         end += length
00404         if python3:
00405           val1 = str[start:end].decode('utf-8')
00406         else:
00407           val1 = str[start:end]
00408         self.name.append(val1)
00409       start = end
00410       end += 4
00411       (length,) = _struct_I.unpack(str[start:end])
00412       self.pose = []
00413       for i in range(0, length):
00414         val1 = geometry_msgs.msg.Pose()
00415         _v19 = val1.position
00416         _x = _v19
00417         start = end
00418         end += 24
00419         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00420         _v20 = val1.orientation
00421         _x = _v20
00422         start = end
00423         end += 32
00424         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00425         self.pose.append(val1)
00426       start = end
00427       end += 4
00428       (length,) = _struct_I.unpack(str[start:end])
00429       self.twist = []
00430       for i in range(0, length):
00431         val1 = geometry_msgs.msg.Twist()
00432         _v21 = val1.linear
00433         _x = _v21
00434         start = end
00435         end += 24
00436         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00437         _v22 = val1.angular
00438         _x = _v22
00439         start = end
00440         end += 24
00441         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00442         self.twist.append(val1)
00443       start = end
00444       end += 4
00445       (length,) = _struct_I.unpack(str[start:end])
00446       self.wrench = []
00447       for i in range(0, length):
00448         val1 = geometry_msgs.msg.Wrench()
00449         _v23 = val1.force
00450         _x = _v23
00451         start = end
00452         end += 24
00453         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00454         _v24 = val1.torque
00455         _x = _v24
00456         start = end
00457         end += 24
00458         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00459         self.wrench.append(val1)
00460       return self
00461     except struct.error as e:
00462       raise genpy.DeserializationError(e) #most likely buffer underfill
00463 
00464 _struct_I = genpy.struct_I
00465 _struct_3I = struct.Struct("<3I")
00466 _struct_4d = struct.Struct("<4d")
00467 _struct_3d = struct.Struct("<3d")


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