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