00001 """autogenerated by genmsg_py from JointStateList.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import dynamixel_msgs.msg
00006 import std_msgs.msg
00007
00008 class JointStateList(roslib.message.Message):
00009 _md5sum = "39b7d137ea0a3aade285e88b8dd58dfe"
00010 _type = "dynamixel_msgs/JointStateList"
00011 _has_header = False
00012 _full_text = """JointState[] motor_states
00013
00014 ================================================================================
00015 MSG: dynamixel_msgs/JointState
00016 Header header
00017 string name # joint name
00018 int32[] motor_ids # motor ids controlling this joint
00019 int32[] motor_temps # motor temperatures, same order as motor_ids
00020
00021 float64 goal_pos # commanded position (in radians)
00022 float64 current_pos # current joint position (in radians)
00023 float64 error # error between commanded and current positions (in radians)
00024 float64 velocity # current joint speed (in radians per second)
00025 float64 load # current load
00026 bool is_moving # is joint currently in motion
00027
00028
00029 ================================================================================
00030 MSG: std_msgs/Header
00031 # Standard metadata for higher-level stamped data types.
00032 # This is generally used to communicate timestamped data
00033 # in a particular coordinate frame.
00034 #
00035 # sequence ID: consecutively increasing ID
00036 uint32 seq
00037 #Two-integer timestamp that is expressed as:
00038 # * stamp.secs: seconds (stamp_secs) since epoch
00039 # * stamp.nsecs: nanoseconds since stamp_secs
00040 # time-handling sugar is provided by the client library
00041 time stamp
00042 #Frame this data is associated with
00043 # 0: no frame
00044 # 1: global frame
00045 string frame_id
00046
00047 """
00048 __slots__ = ['motor_states']
00049 _slot_types = ['dynamixel_msgs/JointState[]']
00050
00051 def __init__(self, *args, **kwds):
00052 """
00053 Constructor. Any message fields that are implicitly/explicitly
00054 set to None will be assigned a default value. The recommend
00055 use is keyword arguments as this is more robust to future message
00056 changes. You cannot mix in-order arguments and keyword arguments.
00057
00058 The available fields are:
00059 motor_states
00060
00061 @param args: complete set of field values, in .msg order
00062 @param kwds: use keyword arguments corresponding to message field names
00063 to set specific fields.
00064 """
00065 if args or kwds:
00066 super(JointStateList, self).__init__(*args, **kwds)
00067
00068 if self.motor_states is None:
00069 self.motor_states = []
00070 else:
00071 self.motor_states = []
00072
00073 def _get_types(self):
00074 """
00075 internal API method
00076 """
00077 return self._slot_types
00078
00079 def serialize(self, buff):
00080 """
00081 serialize message into buffer
00082 @param buff: buffer
00083 @type buff: StringIO
00084 """
00085 try:
00086 length = len(self.motor_states)
00087 buff.write(_struct_I.pack(length))
00088 for val1 in self.motor_states:
00089 _v1 = val1.header
00090 buff.write(_struct_I.pack(_v1.seq))
00091 _v2 = _v1.stamp
00092 _x = _v2
00093 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00094 _x = _v1.frame_id
00095 length = len(_x)
00096 buff.write(struct.pack('<I%ss'%length, length, _x))
00097 _x = val1.name
00098 length = len(_x)
00099 buff.write(struct.pack('<I%ss'%length, length, _x))
00100 length = len(val1.motor_ids)
00101 buff.write(_struct_I.pack(length))
00102 pattern = '<%si'%length
00103 buff.write(struct.pack(pattern, *val1.motor_ids))
00104 length = len(val1.motor_temps)
00105 buff.write(_struct_I.pack(length))
00106 pattern = '<%si'%length
00107 buff.write(struct.pack(pattern, *val1.motor_temps))
00108 _x = val1
00109 buff.write(_struct_5dB.pack(_x.goal_pos, _x.current_pos, _x.error, _x.velocity, _x.load, _x.is_moving))
00110 except struct.error, se: self._check_types(se)
00111 except TypeError, te: self._check_types(te)
00112
00113 def deserialize(self, str):
00114 """
00115 unpack serialized message in str into this message instance
00116 @param str: byte array of serialized message
00117 @type str: str
00118 """
00119 try:
00120 end = 0
00121 start = end
00122 end += 4
00123 (length,) = _struct_I.unpack(str[start:end])
00124 self.motor_states = []
00125 for i in xrange(0, length):
00126 val1 = dynamixel_msgs.msg.JointState()
00127 _v3 = val1.header
00128 start = end
00129 end += 4
00130 (_v3.seq,) = _struct_I.unpack(str[start:end])
00131 _v4 = _v3.stamp
00132 _x = _v4
00133 start = end
00134 end += 8
00135 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00136 start = end
00137 end += 4
00138 (length,) = _struct_I.unpack(str[start:end])
00139 start = end
00140 end += length
00141 _v3.frame_id = str[start:end]
00142 start = end
00143 end += 4
00144 (length,) = _struct_I.unpack(str[start:end])
00145 start = end
00146 end += length
00147 val1.name = str[start:end]
00148 start = end
00149 end += 4
00150 (length,) = _struct_I.unpack(str[start:end])
00151 pattern = '<%si'%length
00152 start = end
00153 end += struct.calcsize(pattern)
00154 val1.motor_ids = struct.unpack(pattern, str[start:end])
00155 start = end
00156 end += 4
00157 (length,) = _struct_I.unpack(str[start:end])
00158 pattern = '<%si'%length
00159 start = end
00160 end += struct.calcsize(pattern)
00161 val1.motor_temps = struct.unpack(pattern, str[start:end])
00162 _x = val1
00163 start = end
00164 end += 41
00165 (_x.goal_pos, _x.current_pos, _x.error, _x.velocity, _x.load, _x.is_moving,) = _struct_5dB.unpack(str[start:end])
00166 val1.is_moving = bool(val1.is_moving)
00167 self.motor_states.append(val1)
00168 return self
00169 except struct.error, e:
00170 raise roslib.message.DeserializationError(e)
00171
00172
00173 def serialize_numpy(self, buff, numpy):
00174 """
00175 serialize message with numpy array types into buffer
00176 @param buff: buffer
00177 @type buff: StringIO
00178 @param numpy: numpy python module
00179 @type numpy module
00180 """
00181 try:
00182 length = len(self.motor_states)
00183 buff.write(_struct_I.pack(length))
00184 for val1 in self.motor_states:
00185 _v5 = val1.header
00186 buff.write(_struct_I.pack(_v5.seq))
00187 _v6 = _v5.stamp
00188 _x = _v6
00189 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00190 _x = _v5.frame_id
00191 length = len(_x)
00192 buff.write(struct.pack('<I%ss'%length, length, _x))
00193 _x = val1.name
00194 length = len(_x)
00195 buff.write(struct.pack('<I%ss'%length, length, _x))
00196 length = len(val1.motor_ids)
00197 buff.write(_struct_I.pack(length))
00198 pattern = '<%si'%length
00199 buff.write(val1.motor_ids.tostring())
00200 length = len(val1.motor_temps)
00201 buff.write(_struct_I.pack(length))
00202 pattern = '<%si'%length
00203 buff.write(val1.motor_temps.tostring())
00204 _x = val1
00205 buff.write(_struct_5dB.pack(_x.goal_pos, _x.current_pos, _x.error, _x.velocity, _x.load, _x.is_moving))
00206 except struct.error, se: self._check_types(se)
00207 except TypeError, te: self._check_types(te)
00208
00209 def deserialize_numpy(self, str, numpy):
00210 """
00211 unpack serialized message in str into this message instance using numpy for array types
00212 @param str: byte array of serialized message
00213 @type str: str
00214 @param numpy: numpy python module
00215 @type numpy: module
00216 """
00217 try:
00218 end = 0
00219 start = end
00220 end += 4
00221 (length,) = _struct_I.unpack(str[start:end])
00222 self.motor_states = []
00223 for i in xrange(0, length):
00224 val1 = dynamixel_msgs.msg.JointState()
00225 _v7 = val1.header
00226 start = end
00227 end += 4
00228 (_v7.seq,) = _struct_I.unpack(str[start:end])
00229 _v8 = _v7.stamp
00230 _x = _v8
00231 start = end
00232 end += 8
00233 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00234 start = end
00235 end += 4
00236 (length,) = _struct_I.unpack(str[start:end])
00237 start = end
00238 end += length
00239 _v7.frame_id = str[start:end]
00240 start = end
00241 end += 4
00242 (length,) = _struct_I.unpack(str[start:end])
00243 start = end
00244 end += length
00245 val1.name = str[start:end]
00246 start = end
00247 end += 4
00248 (length,) = _struct_I.unpack(str[start:end])
00249 pattern = '<%si'%length
00250 start = end
00251 end += struct.calcsize(pattern)
00252 val1.motor_ids = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00253 start = end
00254 end += 4
00255 (length,) = _struct_I.unpack(str[start:end])
00256 pattern = '<%si'%length
00257 start = end
00258 end += struct.calcsize(pattern)
00259 val1.motor_temps = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00260 _x = val1
00261 start = end
00262 end += 41
00263 (_x.goal_pos, _x.current_pos, _x.error, _x.velocity, _x.load, _x.is_moving,) = _struct_5dB.unpack(str[start:end])
00264 val1.is_moving = bool(val1.is_moving)
00265 self.motor_states.append(val1)
00266 return self
00267 except struct.error, e:
00268 raise roslib.message.DeserializationError(e)
00269
00270 _struct_I = roslib.message.struct_I
00271 _struct_5dB = struct.Struct("<5dB")
00272 _struct_2I = struct.Struct("<2I")