00001 """autogenerated by genpy from control_msgs/FollowJointTrajectoryFeedback.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 trajectory_msgs.msg
00008 import genpy
00009 import std_msgs.msg
00010
00011 class FollowJointTrajectoryFeedback(genpy.Message):
00012 _md5sum = "b11d532a92ee589417fdd76559eb1d9e"
00013 _type = "control_msgs/FollowJointTrajectoryFeedback"
00014 _has_header = True
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016 Header header
00017 string[] joint_names
00018 trajectory_msgs/JointTrajectoryPoint desired
00019 trajectory_msgs/JointTrajectoryPoint actual
00020 trajectory_msgs/JointTrajectoryPoint error
00021
00022
00023 ================================================================================
00024 MSG: std_msgs/Header
00025 # Standard metadata for higher-level stamped data types.
00026 # This is generally used to communicate timestamped data
00027 # in a particular coordinate frame.
00028 #
00029 # sequence ID: consecutively increasing ID
00030 uint32 seq
00031 #Two-integer timestamp that is expressed as:
00032 # * stamp.secs: seconds (stamp_secs) since epoch
00033 # * stamp.nsecs: nanoseconds since stamp_secs
00034 # time-handling sugar is provided by the client library
00035 time stamp
00036 #Frame this data is associated with
00037 # 0: no frame
00038 # 1: global frame
00039 string frame_id
00040
00041 ================================================================================
00042 MSG: trajectory_msgs/JointTrajectoryPoint
00043 float64[] positions
00044 float64[] velocities
00045 float64[] accelerations
00046 duration time_from_start
00047 """
00048 __slots__ = ['header','joint_names','desired','actual','error']
00049 _slot_types = ['std_msgs/Header','string[]','trajectory_msgs/JointTrajectoryPoint','trajectory_msgs/JointTrajectoryPoint','trajectory_msgs/JointTrajectoryPoint']
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 header,joint_names,desired,actual,error
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(FollowJointTrajectoryFeedback, self).__init__(*args, **kwds)
00067
00068 if self.header is None:
00069 self.header = std_msgs.msg.Header()
00070 if self.joint_names is None:
00071 self.joint_names = []
00072 if self.desired is None:
00073 self.desired = trajectory_msgs.msg.JointTrajectoryPoint()
00074 if self.actual is None:
00075 self.actual = trajectory_msgs.msg.JointTrajectoryPoint()
00076 if self.error is None:
00077 self.error = trajectory_msgs.msg.JointTrajectoryPoint()
00078 else:
00079 self.header = std_msgs.msg.Header()
00080 self.joint_names = []
00081 self.desired = trajectory_msgs.msg.JointTrajectoryPoint()
00082 self.actual = trajectory_msgs.msg.JointTrajectoryPoint()
00083 self.error = trajectory_msgs.msg.JointTrajectoryPoint()
00084
00085 def _get_types(self):
00086 """
00087 internal API method
00088 """
00089 return self._slot_types
00090
00091 def serialize(self, buff):
00092 """
00093 serialize message into buffer
00094 :param buff: buffer, ``StringIO``
00095 """
00096 try:
00097 _x = self
00098 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00099 _x = self.header.frame_id
00100 length = len(_x)
00101 if python3 or type(_x) == unicode:
00102 _x = _x.encode('utf-8')
00103 length = len(_x)
00104 buff.write(struct.pack('<I%ss'%length, length, _x))
00105 length = len(self.joint_names)
00106 buff.write(_struct_I.pack(length))
00107 for val1 in self.joint_names:
00108 length = len(val1)
00109 if python3 or type(val1) == unicode:
00110 val1 = val1.encode('utf-8')
00111 length = len(val1)
00112 buff.write(struct.pack('<I%ss'%length, length, val1))
00113 length = len(self.desired.positions)
00114 buff.write(_struct_I.pack(length))
00115 pattern = '<%sd'%length
00116 buff.write(struct.pack(pattern, *self.desired.positions))
00117 length = len(self.desired.velocities)
00118 buff.write(_struct_I.pack(length))
00119 pattern = '<%sd'%length
00120 buff.write(struct.pack(pattern, *self.desired.velocities))
00121 length = len(self.desired.accelerations)
00122 buff.write(_struct_I.pack(length))
00123 pattern = '<%sd'%length
00124 buff.write(struct.pack(pattern, *self.desired.accelerations))
00125 _x = self
00126 buff.write(_struct_2i.pack(_x.desired.time_from_start.secs, _x.desired.time_from_start.nsecs))
00127 length = len(self.actual.positions)
00128 buff.write(_struct_I.pack(length))
00129 pattern = '<%sd'%length
00130 buff.write(struct.pack(pattern, *self.actual.positions))
00131 length = len(self.actual.velocities)
00132 buff.write(_struct_I.pack(length))
00133 pattern = '<%sd'%length
00134 buff.write(struct.pack(pattern, *self.actual.velocities))
00135 length = len(self.actual.accelerations)
00136 buff.write(_struct_I.pack(length))
00137 pattern = '<%sd'%length
00138 buff.write(struct.pack(pattern, *self.actual.accelerations))
00139 _x = self
00140 buff.write(_struct_2i.pack(_x.actual.time_from_start.secs, _x.actual.time_from_start.nsecs))
00141 length = len(self.error.positions)
00142 buff.write(_struct_I.pack(length))
00143 pattern = '<%sd'%length
00144 buff.write(struct.pack(pattern, *self.error.positions))
00145 length = len(self.error.velocities)
00146 buff.write(_struct_I.pack(length))
00147 pattern = '<%sd'%length
00148 buff.write(struct.pack(pattern, *self.error.velocities))
00149 length = len(self.error.accelerations)
00150 buff.write(_struct_I.pack(length))
00151 pattern = '<%sd'%length
00152 buff.write(struct.pack(pattern, *self.error.accelerations))
00153 _x = self
00154 buff.write(_struct_2i.pack(_x.error.time_from_start.secs, _x.error.time_from_start.nsecs))
00155 except struct.error as se: self._check_types(se)
00156 except TypeError as te: self._check_types(te)
00157
00158 def deserialize(self, str):
00159 """
00160 unpack serialized message in str into this message instance
00161 :param str: byte array of serialized message, ``str``
00162 """
00163 try:
00164 if self.header is None:
00165 self.header = std_msgs.msg.Header()
00166 if self.desired is None:
00167 self.desired = trajectory_msgs.msg.JointTrajectoryPoint()
00168 if self.actual is None:
00169 self.actual = trajectory_msgs.msg.JointTrajectoryPoint()
00170 if self.error is None:
00171 self.error = trajectory_msgs.msg.JointTrajectoryPoint()
00172 end = 0
00173 _x = self
00174 start = end
00175 end += 12
00176 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00177 start = end
00178 end += 4
00179 (length,) = _struct_I.unpack(str[start:end])
00180 start = end
00181 end += length
00182 if python3:
00183 self.header.frame_id = str[start:end].decode('utf-8')
00184 else:
00185 self.header.frame_id = str[start:end]
00186 start = end
00187 end += 4
00188 (length,) = _struct_I.unpack(str[start:end])
00189 self.joint_names = []
00190 for i in range(0, length):
00191 start = end
00192 end += 4
00193 (length,) = _struct_I.unpack(str[start:end])
00194 start = end
00195 end += length
00196 if python3:
00197 val1 = str[start:end].decode('utf-8')
00198 else:
00199 val1 = str[start:end]
00200 self.joint_names.append(val1)
00201 start = end
00202 end += 4
00203 (length,) = _struct_I.unpack(str[start:end])
00204 pattern = '<%sd'%length
00205 start = end
00206 end += struct.calcsize(pattern)
00207 self.desired.positions = struct.unpack(pattern, str[start:end])
00208 start = end
00209 end += 4
00210 (length,) = _struct_I.unpack(str[start:end])
00211 pattern = '<%sd'%length
00212 start = end
00213 end += struct.calcsize(pattern)
00214 self.desired.velocities = struct.unpack(pattern, str[start:end])
00215 start = end
00216 end += 4
00217 (length,) = _struct_I.unpack(str[start:end])
00218 pattern = '<%sd'%length
00219 start = end
00220 end += struct.calcsize(pattern)
00221 self.desired.accelerations = struct.unpack(pattern, str[start:end])
00222 _x = self
00223 start = end
00224 end += 8
00225 (_x.desired.time_from_start.secs, _x.desired.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00226 start = end
00227 end += 4
00228 (length,) = _struct_I.unpack(str[start:end])
00229 pattern = '<%sd'%length
00230 start = end
00231 end += struct.calcsize(pattern)
00232 self.actual.positions = struct.unpack(pattern, str[start:end])
00233 start = end
00234 end += 4
00235 (length,) = _struct_I.unpack(str[start:end])
00236 pattern = '<%sd'%length
00237 start = end
00238 end += struct.calcsize(pattern)
00239 self.actual.velocities = struct.unpack(pattern, str[start:end])
00240 start = end
00241 end += 4
00242 (length,) = _struct_I.unpack(str[start:end])
00243 pattern = '<%sd'%length
00244 start = end
00245 end += struct.calcsize(pattern)
00246 self.actual.accelerations = struct.unpack(pattern, str[start:end])
00247 _x = self
00248 start = end
00249 end += 8
00250 (_x.actual.time_from_start.secs, _x.actual.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00251 start = end
00252 end += 4
00253 (length,) = _struct_I.unpack(str[start:end])
00254 pattern = '<%sd'%length
00255 start = end
00256 end += struct.calcsize(pattern)
00257 self.error.positions = struct.unpack(pattern, str[start:end])
00258 start = end
00259 end += 4
00260 (length,) = _struct_I.unpack(str[start:end])
00261 pattern = '<%sd'%length
00262 start = end
00263 end += struct.calcsize(pattern)
00264 self.error.velocities = struct.unpack(pattern, str[start:end])
00265 start = end
00266 end += 4
00267 (length,) = _struct_I.unpack(str[start:end])
00268 pattern = '<%sd'%length
00269 start = end
00270 end += struct.calcsize(pattern)
00271 self.error.accelerations = struct.unpack(pattern, str[start:end])
00272 _x = self
00273 start = end
00274 end += 8
00275 (_x.error.time_from_start.secs, _x.error.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00276 return self
00277 except struct.error as e:
00278 raise genpy.DeserializationError(e)
00279
00280
00281 def serialize_numpy(self, buff, numpy):
00282 """
00283 serialize message with numpy array types into buffer
00284 :param buff: buffer, ``StringIO``
00285 :param numpy: numpy python module
00286 """
00287 try:
00288 _x = self
00289 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00290 _x = self.header.frame_id
00291 length = len(_x)
00292 if python3 or type(_x) == unicode:
00293 _x = _x.encode('utf-8')
00294 length = len(_x)
00295 buff.write(struct.pack('<I%ss'%length, length, _x))
00296 length = len(self.joint_names)
00297 buff.write(_struct_I.pack(length))
00298 for val1 in self.joint_names:
00299 length = len(val1)
00300 if python3 or type(val1) == unicode:
00301 val1 = val1.encode('utf-8')
00302 length = len(val1)
00303 buff.write(struct.pack('<I%ss'%length, length, val1))
00304 length = len(self.desired.positions)
00305 buff.write(_struct_I.pack(length))
00306 pattern = '<%sd'%length
00307 buff.write(self.desired.positions.tostring())
00308 length = len(self.desired.velocities)
00309 buff.write(_struct_I.pack(length))
00310 pattern = '<%sd'%length
00311 buff.write(self.desired.velocities.tostring())
00312 length = len(self.desired.accelerations)
00313 buff.write(_struct_I.pack(length))
00314 pattern = '<%sd'%length
00315 buff.write(self.desired.accelerations.tostring())
00316 _x = self
00317 buff.write(_struct_2i.pack(_x.desired.time_from_start.secs, _x.desired.time_from_start.nsecs))
00318 length = len(self.actual.positions)
00319 buff.write(_struct_I.pack(length))
00320 pattern = '<%sd'%length
00321 buff.write(self.actual.positions.tostring())
00322 length = len(self.actual.velocities)
00323 buff.write(_struct_I.pack(length))
00324 pattern = '<%sd'%length
00325 buff.write(self.actual.velocities.tostring())
00326 length = len(self.actual.accelerations)
00327 buff.write(_struct_I.pack(length))
00328 pattern = '<%sd'%length
00329 buff.write(self.actual.accelerations.tostring())
00330 _x = self
00331 buff.write(_struct_2i.pack(_x.actual.time_from_start.secs, _x.actual.time_from_start.nsecs))
00332 length = len(self.error.positions)
00333 buff.write(_struct_I.pack(length))
00334 pattern = '<%sd'%length
00335 buff.write(self.error.positions.tostring())
00336 length = len(self.error.velocities)
00337 buff.write(_struct_I.pack(length))
00338 pattern = '<%sd'%length
00339 buff.write(self.error.velocities.tostring())
00340 length = len(self.error.accelerations)
00341 buff.write(_struct_I.pack(length))
00342 pattern = '<%sd'%length
00343 buff.write(self.error.accelerations.tostring())
00344 _x = self
00345 buff.write(_struct_2i.pack(_x.error.time_from_start.secs, _x.error.time_from_start.nsecs))
00346 except struct.error as se: self._check_types(se)
00347 except TypeError as te: self._check_types(te)
00348
00349 def deserialize_numpy(self, str, numpy):
00350 """
00351 unpack serialized message in str into this message instance using numpy for array types
00352 :param str: byte array of serialized message, ``str``
00353 :param numpy: numpy python module
00354 """
00355 try:
00356 if self.header is None:
00357 self.header = std_msgs.msg.Header()
00358 if self.desired is None:
00359 self.desired = trajectory_msgs.msg.JointTrajectoryPoint()
00360 if self.actual is None:
00361 self.actual = trajectory_msgs.msg.JointTrajectoryPoint()
00362 if self.error is None:
00363 self.error = trajectory_msgs.msg.JointTrajectoryPoint()
00364 end = 0
00365 _x = self
00366 start = end
00367 end += 12
00368 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 start = end
00373 end += length
00374 if python3:
00375 self.header.frame_id = str[start:end].decode('utf-8')
00376 else:
00377 self.header.frame_id = str[start:end]
00378 start = end
00379 end += 4
00380 (length,) = _struct_I.unpack(str[start:end])
00381 self.joint_names = []
00382 for i in range(0, length):
00383 start = end
00384 end += 4
00385 (length,) = _struct_I.unpack(str[start:end])
00386 start = end
00387 end += length
00388 if python3:
00389 val1 = str[start:end].decode('utf-8')
00390 else:
00391 val1 = str[start:end]
00392 self.joint_names.append(val1)
00393 start = end
00394 end += 4
00395 (length,) = _struct_I.unpack(str[start:end])
00396 pattern = '<%sd'%length
00397 start = end
00398 end += struct.calcsize(pattern)
00399 self.desired.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00400 start = end
00401 end += 4
00402 (length,) = _struct_I.unpack(str[start:end])
00403 pattern = '<%sd'%length
00404 start = end
00405 end += struct.calcsize(pattern)
00406 self.desired.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 pattern = '<%sd'%length
00411 start = end
00412 end += struct.calcsize(pattern)
00413 self.desired.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00414 _x = self
00415 start = end
00416 end += 8
00417 (_x.desired.time_from_start.secs, _x.desired.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00418 start = end
00419 end += 4
00420 (length,) = _struct_I.unpack(str[start:end])
00421 pattern = '<%sd'%length
00422 start = end
00423 end += struct.calcsize(pattern)
00424 self.actual.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00425 start = end
00426 end += 4
00427 (length,) = _struct_I.unpack(str[start:end])
00428 pattern = '<%sd'%length
00429 start = end
00430 end += struct.calcsize(pattern)
00431 self.actual.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00432 start = end
00433 end += 4
00434 (length,) = _struct_I.unpack(str[start:end])
00435 pattern = '<%sd'%length
00436 start = end
00437 end += struct.calcsize(pattern)
00438 self.actual.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00439 _x = self
00440 start = end
00441 end += 8
00442 (_x.actual.time_from_start.secs, _x.actual.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00443 start = end
00444 end += 4
00445 (length,) = _struct_I.unpack(str[start:end])
00446 pattern = '<%sd'%length
00447 start = end
00448 end += struct.calcsize(pattern)
00449 self.error.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00450 start = end
00451 end += 4
00452 (length,) = _struct_I.unpack(str[start:end])
00453 pattern = '<%sd'%length
00454 start = end
00455 end += struct.calcsize(pattern)
00456 self.error.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00457 start = end
00458 end += 4
00459 (length,) = _struct_I.unpack(str[start:end])
00460 pattern = '<%sd'%length
00461 start = end
00462 end += struct.calcsize(pattern)
00463 self.error.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00464 _x = self
00465 start = end
00466 end += 8
00467 (_x.error.time_from_start.secs, _x.error.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00468 return self
00469 except struct.error as e:
00470 raise genpy.DeserializationError(e)
00471
00472 _struct_I = genpy.struct_I
00473 _struct_3I = struct.Struct("<3I")
00474 _struct_2i = struct.Struct("<2i")