_RobotState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from arm_navigation_msgs/RobotState.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 import genpy
00011 import sensor_msgs.msg
00012 
00013 class RobotState(genpy.Message):
00014   _md5sum = "970d46b2ca41b9686adbdaeb592d97a7"
00015   _type = "arm_navigation_msgs/RobotState"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """# This message contains information about the robot state, i.e. the positions of its joints and links
00018 sensor_msgs/JointState joint_state
00019 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00020 
00021 ================================================================================
00022 MSG: sensor_msgs/JointState
00023 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00024 #
00025 # The state of each joint (revolute or prismatic) is defined by:
00026 #  * the position of the joint (rad or m),
00027 #  * the velocity of the joint (rad/s or m/s) and 
00028 #  * the effort that is applied in the joint (Nm or N).
00029 #
00030 # Each joint is uniquely identified by its name
00031 # The header specifies the time at which the joint states were recorded. All the joint states
00032 # in one message have to be recorded at the same time.
00033 #
00034 # This message consists of a multiple arrays, one for each part of the joint state. 
00035 # The goal is to make each of the fields optional. When e.g. your joints have no
00036 # effort associated with them, you can leave the effort array empty. 
00037 #
00038 # All arrays in this message should have the same size, or be empty.
00039 # This is the only way to uniquely associate the joint name with the correct
00040 # states.
00041 
00042 
00043 Header header
00044 
00045 string[] name
00046 float64[] position
00047 float64[] velocity
00048 float64[] effort
00049 
00050 ================================================================================
00051 MSG: std_msgs/Header
00052 # Standard metadata for higher-level stamped data types.
00053 # This is generally used to communicate timestamped data 
00054 # in a particular coordinate frame.
00055 # 
00056 # sequence ID: consecutively increasing ID 
00057 uint32 seq
00058 #Two-integer timestamp that is expressed as:
00059 # * stamp.secs: seconds (stamp_secs) since epoch
00060 # * stamp.nsecs: nanoseconds since stamp_secs
00061 # time-handling sugar is provided by the client library
00062 time stamp
00063 #Frame this data is associated with
00064 # 0: no frame
00065 # 1: global frame
00066 string frame_id
00067 
00068 ================================================================================
00069 MSG: arm_navigation_msgs/MultiDOFJointState
00070 #A representation of a multi-dof joint state
00071 time stamp
00072 string[] joint_names
00073 string[] frame_ids
00074 string[] child_frame_ids
00075 geometry_msgs/Pose[] poses
00076 
00077 ================================================================================
00078 MSG: geometry_msgs/Pose
00079 # A representation of pose in free space, composed of postion and orientation. 
00080 Point position
00081 Quaternion orientation
00082 
00083 ================================================================================
00084 MSG: geometry_msgs/Point
00085 # This contains the position of a point in free space
00086 float64 x
00087 float64 y
00088 float64 z
00089 
00090 ================================================================================
00091 MSG: geometry_msgs/Quaternion
00092 # This represents an orientation in free space in quaternion form.
00093 
00094 float64 x
00095 float64 y
00096 float64 z
00097 float64 w
00098 
00099 """
00100   __slots__ = ['joint_state','multi_dof_joint_state']
00101   _slot_types = ['sensor_msgs/JointState','arm_navigation_msgs/MultiDOFJointState']
00102 
00103   def __init__(self, *args, **kwds):
00104     """
00105     Constructor. Any message fields that are implicitly/explicitly
00106     set to None will be assigned a default value. The recommend
00107     use is keyword arguments as this is more robust to future message
00108     changes.  You cannot mix in-order arguments and keyword arguments.
00109 
00110     The available fields are:
00111        joint_state,multi_dof_joint_state
00112 
00113     :param args: complete set of field values, in .msg order
00114     :param kwds: use keyword arguments corresponding to message field names
00115     to set specific fields.
00116     """
00117     if args or kwds:
00118       super(RobotState, self).__init__(*args, **kwds)
00119       #message fields cannot be None, assign default values for those that are
00120       if self.joint_state is None:
00121         self.joint_state = sensor_msgs.msg.JointState()
00122       if self.multi_dof_joint_state is None:
00123         self.multi_dof_joint_state = arm_navigation_msgs.msg.MultiDOFJointState()
00124     else:
00125       self.joint_state = sensor_msgs.msg.JointState()
00126       self.multi_dof_joint_state = arm_navigation_msgs.msg.MultiDOFJointState()
00127 
00128   def _get_types(self):
00129     """
00130     internal API method
00131     """
00132     return self._slot_types
00133 
00134   def serialize(self, buff):
00135     """
00136     serialize message into buffer
00137     :param buff: buffer, ``StringIO``
00138     """
00139     try:
00140       _x = self
00141       buff.write(_struct_3I.pack(_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs))
00142       _x = self.joint_state.header.frame_id
00143       length = len(_x)
00144       if python3 or type(_x) == unicode:
00145         _x = _x.encode('utf-8')
00146         length = len(_x)
00147       buff.write(struct.pack('<I%ss'%length, length, _x))
00148       length = len(self.joint_state.name)
00149       buff.write(_struct_I.pack(length))
00150       for val1 in self.joint_state.name:
00151         length = len(val1)
00152         if python3 or type(val1) == unicode:
00153           val1 = val1.encode('utf-8')
00154           length = len(val1)
00155         buff.write(struct.pack('<I%ss'%length, length, val1))
00156       length = len(self.joint_state.position)
00157       buff.write(_struct_I.pack(length))
00158       pattern = '<%sd'%length
00159       buff.write(struct.pack(pattern, *self.joint_state.position))
00160       length = len(self.joint_state.velocity)
00161       buff.write(_struct_I.pack(length))
00162       pattern = '<%sd'%length
00163       buff.write(struct.pack(pattern, *self.joint_state.velocity))
00164       length = len(self.joint_state.effort)
00165       buff.write(_struct_I.pack(length))
00166       pattern = '<%sd'%length
00167       buff.write(struct.pack(pattern, *self.joint_state.effort))
00168       _x = self
00169       buff.write(_struct_2I.pack(_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs))
00170       length = len(self.multi_dof_joint_state.joint_names)
00171       buff.write(_struct_I.pack(length))
00172       for val1 in self.multi_dof_joint_state.joint_names:
00173         length = len(val1)
00174         if python3 or type(val1) == unicode:
00175           val1 = val1.encode('utf-8')
00176           length = len(val1)
00177         buff.write(struct.pack('<I%ss'%length, length, val1))
00178       length = len(self.multi_dof_joint_state.frame_ids)
00179       buff.write(_struct_I.pack(length))
00180       for val1 in self.multi_dof_joint_state.frame_ids:
00181         length = len(val1)
00182         if python3 or type(val1) == unicode:
00183           val1 = val1.encode('utf-8')
00184           length = len(val1)
00185         buff.write(struct.pack('<I%ss'%length, length, val1))
00186       length = len(self.multi_dof_joint_state.child_frame_ids)
00187       buff.write(_struct_I.pack(length))
00188       for val1 in self.multi_dof_joint_state.child_frame_ids:
00189         length = len(val1)
00190         if python3 or type(val1) == unicode:
00191           val1 = val1.encode('utf-8')
00192           length = len(val1)
00193         buff.write(struct.pack('<I%ss'%length, length, val1))
00194       length = len(self.multi_dof_joint_state.poses)
00195       buff.write(_struct_I.pack(length))
00196       for val1 in self.multi_dof_joint_state.poses:
00197         _v1 = val1.position
00198         _x = _v1
00199         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00200         _v2 = val1.orientation
00201         _x = _v2
00202         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00203     except struct.error as se: self._check_types(se)
00204     except TypeError as 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, ``str``
00210     """
00211     try:
00212       if self.joint_state is None:
00213         self.joint_state = sensor_msgs.msg.JointState()
00214       if self.multi_dof_joint_state is None:
00215         self.multi_dof_joint_state = arm_navigation_msgs.msg.MultiDOFJointState()
00216       end = 0
00217       _x = self
00218       start = end
00219       end += 12
00220       (_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00221       start = end
00222       end += 4
00223       (length,) = _struct_I.unpack(str[start:end])
00224       start = end
00225       end += length
00226       if python3:
00227         self.joint_state.header.frame_id = str[start:end].decode('utf-8')
00228       else:
00229         self.joint_state.header.frame_id = str[start:end]
00230       start = end
00231       end += 4
00232       (length,) = _struct_I.unpack(str[start:end])
00233       self.joint_state.name = []
00234       for i in range(0, length):
00235         start = end
00236         end += 4
00237         (length,) = _struct_I.unpack(str[start:end])
00238         start = end
00239         end += length
00240         if python3:
00241           val1 = str[start:end].decode('utf-8')
00242         else:
00243           val1 = str[start:end]
00244         self.joint_state.name.append(val1)
00245       start = end
00246       end += 4
00247       (length,) = _struct_I.unpack(str[start:end])
00248       pattern = '<%sd'%length
00249       start = end
00250       end += struct.calcsize(pattern)
00251       self.joint_state.position = struct.unpack(pattern, str[start:end])
00252       start = end
00253       end += 4
00254       (length,) = _struct_I.unpack(str[start:end])
00255       pattern = '<%sd'%length
00256       start = end
00257       end += struct.calcsize(pattern)
00258       self.joint_state.velocity = struct.unpack(pattern, str[start:end])
00259       start = end
00260       end += 4
00261       (length,) = _struct_I.unpack(str[start:end])
00262       pattern = '<%sd'%length
00263       start = end
00264       end += struct.calcsize(pattern)
00265       self.joint_state.effort = struct.unpack(pattern, str[start:end])
00266       _x = self
00267       start = end
00268       end += 8
00269       (_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00270       start = end
00271       end += 4
00272       (length,) = _struct_I.unpack(str[start:end])
00273       self.multi_dof_joint_state.joint_names = []
00274       for i in range(0, length):
00275         start = end
00276         end += 4
00277         (length,) = _struct_I.unpack(str[start:end])
00278         start = end
00279         end += length
00280         if python3:
00281           val1 = str[start:end].decode('utf-8')
00282         else:
00283           val1 = str[start:end]
00284         self.multi_dof_joint_state.joint_names.append(val1)
00285       start = end
00286       end += 4
00287       (length,) = _struct_I.unpack(str[start:end])
00288       self.multi_dof_joint_state.frame_ids = []
00289       for i in range(0, length):
00290         start = end
00291         end += 4
00292         (length,) = _struct_I.unpack(str[start:end])
00293         start = end
00294         end += length
00295         if python3:
00296           val1 = str[start:end].decode('utf-8')
00297         else:
00298           val1 = str[start:end]
00299         self.multi_dof_joint_state.frame_ids.append(val1)
00300       start = end
00301       end += 4
00302       (length,) = _struct_I.unpack(str[start:end])
00303       self.multi_dof_joint_state.child_frame_ids = []
00304       for i in range(0, length):
00305         start = end
00306         end += 4
00307         (length,) = _struct_I.unpack(str[start:end])
00308         start = end
00309         end += length
00310         if python3:
00311           val1 = str[start:end].decode('utf-8')
00312         else:
00313           val1 = str[start:end]
00314         self.multi_dof_joint_state.child_frame_ids.append(val1)
00315       start = end
00316       end += 4
00317       (length,) = _struct_I.unpack(str[start:end])
00318       self.multi_dof_joint_state.poses = []
00319       for i in range(0, length):
00320         val1 = geometry_msgs.msg.Pose()
00321         _v3 = val1.position
00322         _x = _v3
00323         start = end
00324         end += 24
00325         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00326         _v4 = val1.orientation
00327         _x = _v4
00328         start = end
00329         end += 32
00330         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00331         self.multi_dof_joint_state.poses.append(val1)
00332       return self
00333     except struct.error as e:
00334       raise genpy.DeserializationError(e) #most likely buffer underfill
00335 
00336 
00337   def serialize_numpy(self, buff, numpy):
00338     """
00339     serialize message with numpy array types into buffer
00340     :param buff: buffer, ``StringIO``
00341     :param numpy: numpy python module
00342     """
00343     try:
00344       _x = self
00345       buff.write(_struct_3I.pack(_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs))
00346       _x = self.joint_state.header.frame_id
00347       length = len(_x)
00348       if python3 or type(_x) == unicode:
00349         _x = _x.encode('utf-8')
00350         length = len(_x)
00351       buff.write(struct.pack('<I%ss'%length, length, _x))
00352       length = len(self.joint_state.name)
00353       buff.write(_struct_I.pack(length))
00354       for val1 in self.joint_state.name:
00355         length = len(val1)
00356         if python3 or type(val1) == unicode:
00357           val1 = val1.encode('utf-8')
00358           length = len(val1)
00359         buff.write(struct.pack('<I%ss'%length, length, val1))
00360       length = len(self.joint_state.position)
00361       buff.write(_struct_I.pack(length))
00362       pattern = '<%sd'%length
00363       buff.write(self.joint_state.position.tostring())
00364       length = len(self.joint_state.velocity)
00365       buff.write(_struct_I.pack(length))
00366       pattern = '<%sd'%length
00367       buff.write(self.joint_state.velocity.tostring())
00368       length = len(self.joint_state.effort)
00369       buff.write(_struct_I.pack(length))
00370       pattern = '<%sd'%length
00371       buff.write(self.joint_state.effort.tostring())
00372       _x = self
00373       buff.write(_struct_2I.pack(_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs))
00374       length = len(self.multi_dof_joint_state.joint_names)
00375       buff.write(_struct_I.pack(length))
00376       for val1 in self.multi_dof_joint_state.joint_names:
00377         length = len(val1)
00378         if python3 or type(val1) == unicode:
00379           val1 = val1.encode('utf-8')
00380           length = len(val1)
00381         buff.write(struct.pack('<I%ss'%length, length, val1))
00382       length = len(self.multi_dof_joint_state.frame_ids)
00383       buff.write(_struct_I.pack(length))
00384       for val1 in self.multi_dof_joint_state.frame_ids:
00385         length = len(val1)
00386         if python3 or type(val1) == unicode:
00387           val1 = val1.encode('utf-8')
00388           length = len(val1)
00389         buff.write(struct.pack('<I%ss'%length, length, val1))
00390       length = len(self.multi_dof_joint_state.child_frame_ids)
00391       buff.write(_struct_I.pack(length))
00392       for val1 in self.multi_dof_joint_state.child_frame_ids:
00393         length = len(val1)
00394         if python3 or type(val1) == unicode:
00395           val1 = val1.encode('utf-8')
00396           length = len(val1)
00397         buff.write(struct.pack('<I%ss'%length, length, val1))
00398       length = len(self.multi_dof_joint_state.poses)
00399       buff.write(_struct_I.pack(length))
00400       for val1 in self.multi_dof_joint_state.poses:
00401         _v5 = val1.position
00402         _x = _v5
00403         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00404         _v6 = val1.orientation
00405         _x = _v6
00406         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00407     except struct.error as se: self._check_types(se)
00408     except TypeError as te: self._check_types(te)
00409 
00410   def deserialize_numpy(self, str, numpy):
00411     """
00412     unpack serialized message in str into this message instance using numpy for array types
00413     :param str: byte array of serialized message, ``str``
00414     :param numpy: numpy python module
00415     """
00416     try:
00417       if self.joint_state is None:
00418         self.joint_state = sensor_msgs.msg.JointState()
00419       if self.multi_dof_joint_state is None:
00420         self.multi_dof_joint_state = arm_navigation_msgs.msg.MultiDOFJointState()
00421       end = 0
00422       _x = self
00423       start = end
00424       end += 12
00425       (_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00426       start = end
00427       end += 4
00428       (length,) = _struct_I.unpack(str[start:end])
00429       start = end
00430       end += length
00431       if python3:
00432         self.joint_state.header.frame_id = str[start:end].decode('utf-8')
00433       else:
00434         self.joint_state.header.frame_id = str[start:end]
00435       start = end
00436       end += 4
00437       (length,) = _struct_I.unpack(str[start:end])
00438       self.joint_state.name = []
00439       for i in range(0, length):
00440         start = end
00441         end += 4
00442         (length,) = _struct_I.unpack(str[start:end])
00443         start = end
00444         end += length
00445         if python3:
00446           val1 = str[start:end].decode('utf-8')
00447         else:
00448           val1 = str[start:end]
00449         self.joint_state.name.append(val1)
00450       start = end
00451       end += 4
00452       (length,) = _struct_I.unpack(str[start:end])
00453       pattern = '<%sd'%length
00454       start = end
00455       end += struct.calcsize(pattern)
00456       self.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00457       start = end
00458       end += 4
00459       (length,) = _struct_I.unpack(str[start:end])
00460       pattern = '<%sd'%length
00461       start = end
00462       end += struct.calcsize(pattern)
00463       self.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00464       start = end
00465       end += 4
00466       (length,) = _struct_I.unpack(str[start:end])
00467       pattern = '<%sd'%length
00468       start = end
00469       end += struct.calcsize(pattern)
00470       self.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00471       _x = self
00472       start = end
00473       end += 8
00474       (_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00475       start = end
00476       end += 4
00477       (length,) = _struct_I.unpack(str[start:end])
00478       self.multi_dof_joint_state.joint_names = []
00479       for i in range(0, length):
00480         start = end
00481         end += 4
00482         (length,) = _struct_I.unpack(str[start:end])
00483         start = end
00484         end += length
00485         if python3:
00486           val1 = str[start:end].decode('utf-8')
00487         else:
00488           val1 = str[start:end]
00489         self.multi_dof_joint_state.joint_names.append(val1)
00490       start = end
00491       end += 4
00492       (length,) = _struct_I.unpack(str[start:end])
00493       self.multi_dof_joint_state.frame_ids = []
00494       for i in range(0, length):
00495         start = end
00496         end += 4
00497         (length,) = _struct_I.unpack(str[start:end])
00498         start = end
00499         end += length
00500         if python3:
00501           val1 = str[start:end].decode('utf-8')
00502         else:
00503           val1 = str[start:end]
00504         self.multi_dof_joint_state.frame_ids.append(val1)
00505       start = end
00506       end += 4
00507       (length,) = _struct_I.unpack(str[start:end])
00508       self.multi_dof_joint_state.child_frame_ids = []
00509       for i in range(0, length):
00510         start = end
00511         end += 4
00512         (length,) = _struct_I.unpack(str[start:end])
00513         start = end
00514         end += length
00515         if python3:
00516           val1 = str[start:end].decode('utf-8')
00517         else:
00518           val1 = str[start:end]
00519         self.multi_dof_joint_state.child_frame_ids.append(val1)
00520       start = end
00521       end += 4
00522       (length,) = _struct_I.unpack(str[start:end])
00523       self.multi_dof_joint_state.poses = []
00524       for i in range(0, length):
00525         val1 = geometry_msgs.msg.Pose()
00526         _v7 = val1.position
00527         _x = _v7
00528         start = end
00529         end += 24
00530         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00531         _v8 = val1.orientation
00532         _x = _v8
00533         start = end
00534         end += 32
00535         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00536         self.multi_dof_joint_state.poses.append(val1)
00537       return self
00538     except struct.error as e:
00539       raise genpy.DeserializationError(e) #most likely buffer underfill
00540 
00541 _struct_I = genpy.struct_I
00542 _struct_4d = struct.Struct("<4d")
00543 _struct_3I = struct.Struct("<3I")
00544 _struct_2I = struct.Struct("<2I")
00545 _struct_3d = struct.Struct("<3d")


arm_navigation_msgs
Author(s): Gil Jones
autogenerated on Mon Dec 2 2013 12:31:50