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


hrpsys_gazebo_msgs
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 23 2013 11:48:59