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