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