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