_LabeledJointState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from nasa_r2_common_msgs/LabeledJointState.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 std_msgs.msg
00008 
00009 class LabeledJointState(genpy.Message):
00010   _md5sum = "dcbf606d25a558e3de2e3c95fa2eaca9"
00011   _type = "nasa_r2_common_msgs/LabeledJointState"
00012   _has_header = True #flag to mark the presence of a Header object
00013   _full_text = """# This is a message that holds data to describe the state of a set of torque controlled joints. 
00014 #
00015 # The state of each joint (revolute or prismatic) is defined by:
00016 #  * the position of the joint (rad or m),
00017 #  * the velocity of the joint (rad/s or m/s) and 
00018 #  * the effort that is applied in the joint (Nm or N).
00019 #
00020 # Each joint is uniquely identified by its name
00021 # The header specifies the time at which the joint states were recorded. All the joint states
00022 # in one message have to be recorded at the same time.
00023 #
00024 # This message consists of a multiple arrays, one for each part of the joint state. 
00025 # The goal is to make each of the fields optional. When e.g. your joints have no
00026 # effort associated with them, you can leave the effort array empty. 
00027 #
00028 # All arrays in this message should have the same size, or be empty.
00029 # This is the only way to uniquely associate the joint name with the correct
00030 # states.
00031 
00032 
00033 Header header
00034 string originator
00035 
00036 string[] name
00037 float64[] position
00038 float64[] velocity
00039 float64[] effort
00040 
00041 ================================================================================
00042 MSG: std_msgs/Header
00043 # Standard metadata for higher-level stamped data types.
00044 # This is generally used to communicate timestamped data 
00045 # in a particular coordinate frame.
00046 # 
00047 # sequence ID: consecutively increasing ID 
00048 uint32 seq
00049 #Two-integer timestamp that is expressed as:
00050 # * stamp.secs: seconds (stamp_secs) since epoch
00051 # * stamp.nsecs: nanoseconds since stamp_secs
00052 # time-handling sugar is provided by the client library
00053 time stamp
00054 #Frame this data is associated with
00055 # 0: no frame
00056 # 1: global frame
00057 string frame_id
00058 
00059 """
00060   __slots__ = ['header','originator','name','position','velocity','effort']
00061   _slot_types = ['std_msgs/Header','string','string[]','float64[]','float64[]','float64[]']
00062 
00063   def __init__(self, *args, **kwds):
00064     """
00065     Constructor. Any message fields that are implicitly/explicitly
00066     set to None will be assigned a default value. The recommend
00067     use is keyword arguments as this is more robust to future message
00068     changes.  You cannot mix in-order arguments and keyword arguments.
00069 
00070     The available fields are:
00071        header,originator,name,position,velocity,effort
00072 
00073     :param args: complete set of field values, in .msg order
00074     :param kwds: use keyword arguments corresponding to message field names
00075     to set specific fields.
00076     """
00077     if args or kwds:
00078       super(LabeledJointState, self).__init__(*args, **kwds)
00079       #message fields cannot be None, assign default values for those that are
00080       if self.header is None:
00081         self.header = std_msgs.msg.Header()
00082       if self.originator is None:
00083         self.originator = ''
00084       if self.name is None:
00085         self.name = []
00086       if self.position is None:
00087         self.position = []
00088       if self.velocity is None:
00089         self.velocity = []
00090       if self.effort is None:
00091         self.effort = []
00092     else:
00093       self.header = std_msgs.msg.Header()
00094       self.originator = ''
00095       self.name = []
00096       self.position = []
00097       self.velocity = []
00098       self.effort = []
00099 
00100   def _get_types(self):
00101     """
00102     internal API method
00103     """
00104     return self._slot_types
00105 
00106   def serialize(self, buff):
00107     """
00108     serialize message into buffer
00109     :param buff: buffer, ``StringIO``
00110     """
00111     try:
00112       _x = self
00113       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00114       _x = self.header.frame_id
00115       length = len(_x)
00116       if python3 or type(_x) == unicode:
00117         _x = _x.encode('utf-8')
00118         length = len(_x)
00119       buff.write(struct.pack('<I%ss'%length, length, _x))
00120       _x = self.originator
00121       length = len(_x)
00122       if python3 or type(_x) == unicode:
00123         _x = _x.encode('utf-8')
00124         length = len(_x)
00125       buff.write(struct.pack('<I%ss'%length, length, _x))
00126       length = len(self.name)
00127       buff.write(_struct_I.pack(length))
00128       for val1 in self.name:
00129         length = len(val1)
00130         if python3 or type(val1) == unicode:
00131           val1 = val1.encode('utf-8')
00132           length = len(val1)
00133         buff.write(struct.pack('<I%ss'%length, length, val1))
00134       length = len(self.position)
00135       buff.write(_struct_I.pack(length))
00136       pattern = '<%sd'%length
00137       buff.write(struct.pack(pattern, *self.position))
00138       length = len(self.velocity)
00139       buff.write(_struct_I.pack(length))
00140       pattern = '<%sd'%length
00141       buff.write(struct.pack(pattern, *self.velocity))
00142       length = len(self.effort)
00143       buff.write(_struct_I.pack(length))
00144       pattern = '<%sd'%length
00145       buff.write(struct.pack(pattern, *self.effort))
00146     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00147     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00148 
00149   def deserialize(self, str):
00150     """
00151     unpack serialized message in str into this message instance
00152     :param str: byte array of serialized message, ``str``
00153     """
00154     try:
00155       if self.header is None:
00156         self.header = std_msgs.msg.Header()
00157       end = 0
00158       _x = self
00159       start = end
00160       end += 12
00161       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00162       start = end
00163       end += 4
00164       (length,) = _struct_I.unpack(str[start:end])
00165       start = end
00166       end += length
00167       if python3:
00168         self.header.frame_id = str[start:end].decode('utf-8')
00169       else:
00170         self.header.frame_id = str[start:end]
00171       start = end
00172       end += 4
00173       (length,) = _struct_I.unpack(str[start:end])
00174       start = end
00175       end += length
00176       if python3:
00177         self.originator = str[start:end].decode('utf-8')
00178       else:
00179         self.originator = str[start:end]
00180       start = end
00181       end += 4
00182       (length,) = _struct_I.unpack(str[start:end])
00183       self.name = []
00184       for i in range(0, length):
00185         start = end
00186         end += 4
00187         (length,) = _struct_I.unpack(str[start:end])
00188         start = end
00189         end += length
00190         if python3:
00191           val1 = str[start:end].decode('utf-8')
00192         else:
00193           val1 = str[start:end]
00194         self.name.append(val1)
00195       start = end
00196       end += 4
00197       (length,) = _struct_I.unpack(str[start:end])
00198       pattern = '<%sd'%length
00199       start = end
00200       end += struct.calcsize(pattern)
00201       self.position = struct.unpack(pattern, str[start:end])
00202       start = end
00203       end += 4
00204       (length,) = _struct_I.unpack(str[start:end])
00205       pattern = '<%sd'%length
00206       start = end
00207       end += struct.calcsize(pattern)
00208       self.velocity = struct.unpack(pattern, str[start:end])
00209       start = end
00210       end += 4
00211       (length,) = _struct_I.unpack(str[start:end])
00212       pattern = '<%sd'%length
00213       start = end
00214       end += struct.calcsize(pattern)
00215       self.effort = struct.unpack(pattern, str[start:end])
00216       return self
00217     except struct.error as e:
00218       raise genpy.DeserializationError(e) #most likely buffer underfill
00219 
00220 
00221   def serialize_numpy(self, buff, numpy):
00222     """
00223     serialize message with numpy array types into buffer
00224     :param buff: buffer, ``StringIO``
00225     :param numpy: numpy python module
00226     """
00227     try:
00228       _x = self
00229       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00230       _x = self.header.frame_id
00231       length = len(_x)
00232       if python3 or type(_x) == unicode:
00233         _x = _x.encode('utf-8')
00234         length = len(_x)
00235       buff.write(struct.pack('<I%ss'%length, length, _x))
00236       _x = self.originator
00237       length = len(_x)
00238       if python3 or type(_x) == unicode:
00239         _x = _x.encode('utf-8')
00240         length = len(_x)
00241       buff.write(struct.pack('<I%ss'%length, length, _x))
00242       length = len(self.name)
00243       buff.write(_struct_I.pack(length))
00244       for val1 in self.name:
00245         length = len(val1)
00246         if python3 or type(val1) == unicode:
00247           val1 = val1.encode('utf-8')
00248           length = len(val1)
00249         buff.write(struct.pack('<I%ss'%length, length, val1))
00250       length = len(self.position)
00251       buff.write(_struct_I.pack(length))
00252       pattern = '<%sd'%length
00253       buff.write(self.position.tostring())
00254       length = len(self.velocity)
00255       buff.write(_struct_I.pack(length))
00256       pattern = '<%sd'%length
00257       buff.write(self.velocity.tostring())
00258       length = len(self.effort)
00259       buff.write(_struct_I.pack(length))
00260       pattern = '<%sd'%length
00261       buff.write(self.effort.tostring())
00262     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00263     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00264 
00265   def deserialize_numpy(self, str, numpy):
00266     """
00267     unpack serialized message in str into this message instance using numpy for array types
00268     :param str: byte array of serialized message, ``str``
00269     :param numpy: numpy python module
00270     """
00271     try:
00272       if self.header is None:
00273         self.header = std_msgs.msg.Header()
00274       end = 0
00275       _x = self
00276       start = end
00277       end += 12
00278       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00279       start = end
00280       end += 4
00281       (length,) = _struct_I.unpack(str[start:end])
00282       start = end
00283       end += length
00284       if python3:
00285         self.header.frame_id = str[start:end].decode('utf-8')
00286       else:
00287         self.header.frame_id = str[start:end]
00288       start = end
00289       end += 4
00290       (length,) = _struct_I.unpack(str[start:end])
00291       start = end
00292       end += length
00293       if python3:
00294         self.originator = str[start:end].decode('utf-8')
00295       else:
00296         self.originator = str[start:end]
00297       start = end
00298       end += 4
00299       (length,) = _struct_I.unpack(str[start:end])
00300       self.name = []
00301       for i in range(0, length):
00302         start = end
00303         end += 4
00304         (length,) = _struct_I.unpack(str[start:end])
00305         start = end
00306         end += length
00307         if python3:
00308           val1 = str[start:end].decode('utf-8')
00309         else:
00310           val1 = str[start:end]
00311         self.name.append(val1)
00312       start = end
00313       end += 4
00314       (length,) = _struct_I.unpack(str[start:end])
00315       pattern = '<%sd'%length
00316       start = end
00317       end += struct.calcsize(pattern)
00318       self.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00319       start = end
00320       end += 4
00321       (length,) = _struct_I.unpack(str[start:end])
00322       pattern = '<%sd'%length
00323       start = end
00324       end += struct.calcsize(pattern)
00325       self.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00326       start = end
00327       end += 4
00328       (length,) = _struct_I.unpack(str[start:end])
00329       pattern = '<%sd'%length
00330       start = end
00331       end += struct.calcsize(pattern)
00332       self.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00333       return self
00334     except struct.error as e:
00335       raise genpy.DeserializationError(e) #most likely buffer underfill
00336 
00337 _struct_I = genpy.struct_I
00338 _struct_3I = struct.Struct("<3I")


nasa_r2_common_msgs
Author(s): Paul Dinh. Maintained by Jennifer Turner
autogenerated on Mon Oct 6 2014 02:42:34