00001 """autogenerated by genpy from pr2_mechanism_msgs/JointStatistics.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 genpy
00008
00009 class JointStatistics(genpy.Message):
00010 _md5sum = "90fdc8acbce5bc783d8b4aec49af6590"
00011 _type = "pr2_mechanism_msgs/JointStatistics"
00012 _has_header = False
00013 _full_text = """# This message contains the state of one joint of the pr2 robot.
00014 # This message is specificly designed for the pr2 robot.
00015 # A generic joint state message can be found in sensor_msgs::JointState
00016
00017 # the name of the joint
00018 string name
00019
00020 # the time at which these joint statistics were measured
00021 time timestamp
00022
00023 # the position of the joint in radians
00024 float64 position
00025
00026 # the velocity of the joint in radians per second
00027 float64 velocity
00028
00029 # the measured joint effort
00030 float64 measured_effort
00031
00032 # the effort that was commanded to the joint.
00033 # the actual applied effort might be different
00034 # because the safety code can limit the effort
00035 # a joint can apply
00036 float64 commanded_effort
00037
00038 # a flag indicating if the joint is calibrated or not
00039 bool is_calibrated
00040
00041 # a flag inidcating if the joint violated one of its position/velocity/effort limits
00042 # in the last publish cycle
00043 bool violated_limits
00044
00045 # the total distance travelled by the joint, measured in radians.
00046 float64 odometer
00047
00048 # the lowest position reached by the joint in the last publish cycle
00049 float64 min_position
00050
00051 # the highest position reached by the joint in the last publish cycle
00052 float64 max_position
00053
00054 # the maximum absolute velocity reached by the joint in the last publish cycle
00055 float64 max_abs_velocity
00056
00057 # the maximum absolute effort applied by the joint in the last publish cycle
00058 float64 max_abs_effort
00059
00060 """
00061 __slots__ = ['name','timestamp','position','velocity','measured_effort','commanded_effort','is_calibrated','violated_limits','odometer','min_position','max_position','max_abs_velocity','max_abs_effort']
00062 _slot_types = ['string','time','float64','float64','float64','float64','bool','bool','float64','float64','float64','float64','float64']
00063
00064 def __init__(self, *args, **kwds):
00065 """
00066 Constructor. Any message fields that are implicitly/explicitly
00067 set to None will be assigned a default value. The recommend
00068 use is keyword arguments as this is more robust to future message
00069 changes. You cannot mix in-order arguments and keyword arguments.
00070
00071 The available fields are:
00072 name,timestamp,position,velocity,measured_effort,commanded_effort,is_calibrated,violated_limits,odometer,min_position,max_position,max_abs_velocity,max_abs_effort
00073
00074 :param args: complete set of field values, in .msg order
00075 :param kwds: use keyword arguments corresponding to message field names
00076 to set specific fields.
00077 """
00078 if args or kwds:
00079 super(JointStatistics, self).__init__(*args, **kwds)
00080
00081 if self.name is None:
00082 self.name = ''
00083 if self.timestamp is None:
00084 self.timestamp = genpy.Time()
00085 if self.position is None:
00086 self.position = 0.
00087 if self.velocity is None:
00088 self.velocity = 0.
00089 if self.measured_effort is None:
00090 self.measured_effort = 0.
00091 if self.commanded_effort is None:
00092 self.commanded_effort = 0.
00093 if self.is_calibrated is None:
00094 self.is_calibrated = False
00095 if self.violated_limits is None:
00096 self.violated_limits = False
00097 if self.odometer is None:
00098 self.odometer = 0.
00099 if self.min_position is None:
00100 self.min_position = 0.
00101 if self.max_position is None:
00102 self.max_position = 0.
00103 if self.max_abs_velocity is None:
00104 self.max_abs_velocity = 0.
00105 if self.max_abs_effort is None:
00106 self.max_abs_effort = 0.
00107 else:
00108 self.name = ''
00109 self.timestamp = genpy.Time()
00110 self.position = 0.
00111 self.velocity = 0.
00112 self.measured_effort = 0.
00113 self.commanded_effort = 0.
00114 self.is_calibrated = False
00115 self.violated_limits = False
00116 self.odometer = 0.
00117 self.min_position = 0.
00118 self.max_position = 0.
00119 self.max_abs_velocity = 0.
00120 self.max_abs_effort = 0.
00121
00122 def _get_types(self):
00123 """
00124 internal API method
00125 """
00126 return self._slot_types
00127
00128 def serialize(self, buff):
00129 """
00130 serialize message into buffer
00131 :param buff: buffer, ``StringIO``
00132 """
00133 try:
00134 _x = self.name
00135 length = len(_x)
00136 if python3 or type(_x) == unicode:
00137 _x = _x.encode('utf-8')
00138 length = len(_x)
00139 buff.write(struct.pack('<I%ss'%length, length, _x))
00140 _x = self
00141 buff.write(_struct_2I4d2B5d.pack(_x.timestamp.secs, _x.timestamp.nsecs, _x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort))
00142 except struct.error as se: self._check_types(se)
00143 except TypeError as te: self._check_types(te)
00144
00145 def deserialize(self, str):
00146 """
00147 unpack serialized message in str into this message instance
00148 :param str: byte array of serialized message, ``str``
00149 """
00150 try:
00151 if self.timestamp is None:
00152 self.timestamp = genpy.Time()
00153 end = 0
00154 start = end
00155 end += 4
00156 (length,) = _struct_I.unpack(str[start:end])
00157 start = end
00158 end += length
00159 if python3:
00160 self.name = str[start:end].decode('utf-8')
00161 else:
00162 self.name = str[start:end]
00163 _x = self
00164 start = end
00165 end += 82
00166 (_x.timestamp.secs, _x.timestamp.nsecs, _x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort,) = _struct_2I4d2B5d.unpack(str[start:end])
00167 self.is_calibrated = bool(self.is_calibrated)
00168 self.violated_limits = bool(self.violated_limits)
00169 self.timestamp.canon()
00170 return self
00171 except struct.error as e:
00172 raise genpy.DeserializationError(e)
00173
00174
00175 def serialize_numpy(self, buff, numpy):
00176 """
00177 serialize message with numpy array types into buffer
00178 :param buff: buffer, ``StringIO``
00179 :param numpy: numpy python module
00180 """
00181 try:
00182 _x = self.name
00183 length = len(_x)
00184 if python3 or type(_x) == unicode:
00185 _x = _x.encode('utf-8')
00186 length = len(_x)
00187 buff.write(struct.pack('<I%ss'%length, length, _x))
00188 _x = self
00189 buff.write(_struct_2I4d2B5d.pack(_x.timestamp.secs, _x.timestamp.nsecs, _x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort))
00190 except struct.error as se: self._check_types(se)
00191 except TypeError as te: self._check_types(te)
00192
00193 def deserialize_numpy(self, str, numpy):
00194 """
00195 unpack serialized message in str into this message instance using numpy for array types
00196 :param str: byte array of serialized message, ``str``
00197 :param numpy: numpy python module
00198 """
00199 try:
00200 if self.timestamp is None:
00201 self.timestamp = genpy.Time()
00202 end = 0
00203 start = end
00204 end += 4
00205 (length,) = _struct_I.unpack(str[start:end])
00206 start = end
00207 end += length
00208 if python3:
00209 self.name = str[start:end].decode('utf-8')
00210 else:
00211 self.name = str[start:end]
00212 _x = self
00213 start = end
00214 end += 82
00215 (_x.timestamp.secs, _x.timestamp.nsecs, _x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort,) = _struct_2I4d2B5d.unpack(str[start:end])
00216 self.is_calibrated = bool(self.is_calibrated)
00217 self.violated_limits = bool(self.violated_limits)
00218 self.timestamp.canon()
00219 return self
00220 except struct.error as e:
00221 raise genpy.DeserializationError(e)
00222
00223 _struct_I = genpy.struct_I
00224 _struct_2I4d2B5d = struct.Struct("<2I4d2B5d")