00001 """autogenerated by genpy from nao_msgs/JointTrajectoryActionGoal.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 nao_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import std_msgs.msg
00012
00013 class JointTrajectoryActionGoal(genpy.Message):
00014 _md5sum = "3273243339f8ad806de69e2c87c1e17c"
00015 _type = "nao_msgs/JointTrajectoryActionGoal"
00016 _has_header = True
00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018
00019 Header header
00020 actionlib_msgs/GoalID goal_id
00021 JointTrajectoryGoal goal
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: actionlib_msgs/GoalID
00043 # The stamp should store the time at which this goal was requested.
00044 # It is used by an action server when it tries to preempt all
00045 # goals that were requested before a certain time
00046 time stamp
00047
00048 # The id provides a way to associate feedback and
00049 # result message with specific goal requests. The id
00050 # specified must be unique.
00051 string id
00052
00053
00054 ================================================================================
00055 MSG: nao_msgs/JointTrajectoryGoal
00056 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00057 # goal: a joint angle trajectory
00058 trajectory_msgs/JointTrajectory trajectory
00059 # flag whether motion is absolute (=0, default) or relative (=1)
00060 uint8 relative
00061
00062 ================================================================================
00063 MSG: trajectory_msgs/JointTrajectory
00064 Header header
00065 string[] joint_names
00066 JointTrajectoryPoint[] points
00067 ================================================================================
00068 MSG: trajectory_msgs/JointTrajectoryPoint
00069 float64[] positions
00070 float64[] velocities
00071 float64[] accelerations
00072 duration time_from_start
00073 """
00074 __slots__ = ['header','goal_id','goal']
00075 _slot_types = ['std_msgs/Header','actionlib_msgs/GoalID','nao_msgs/JointTrajectoryGoal']
00076
00077 def __init__(self, *args, **kwds):
00078 """
00079 Constructor. Any message fields that are implicitly/explicitly
00080 set to None will be assigned a default value. The recommend
00081 use is keyword arguments as this is more robust to future message
00082 changes. You cannot mix in-order arguments and keyword arguments.
00083
00084 The available fields are:
00085 header,goal_id,goal
00086
00087 :param args: complete set of field values, in .msg order
00088 :param kwds: use keyword arguments corresponding to message field names
00089 to set specific fields.
00090 """
00091 if args or kwds:
00092 super(JointTrajectoryActionGoal, self).__init__(*args, **kwds)
00093
00094 if self.header is None:
00095 self.header = std_msgs.msg.Header()
00096 if self.goal_id is None:
00097 self.goal_id = actionlib_msgs.msg.GoalID()
00098 if self.goal is None:
00099 self.goal = nao_msgs.msg.JointTrajectoryGoal()
00100 else:
00101 self.header = std_msgs.msg.Header()
00102 self.goal_id = actionlib_msgs.msg.GoalID()
00103 self.goal = nao_msgs.msg.JointTrajectoryGoal()
00104
00105 def _get_types(self):
00106 """
00107 internal API method
00108 """
00109 return self._slot_types
00110
00111 def serialize(self, buff):
00112 """
00113 serialize message into buffer
00114 :param buff: buffer, ``StringIO``
00115 """
00116 try:
00117 _x = self
00118 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00119 _x = self.header.frame_id
00120 length = len(_x)
00121 if python3 or type(_x) == unicode:
00122 _x = _x.encode('utf-8')
00123 length = len(_x)
00124 buff.write(struct.pack('<I%ss'%length, length, _x))
00125 _x = self
00126 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00127 _x = self.goal_id.id
00128 length = len(_x)
00129 if python3 or type(_x) == unicode:
00130 _x = _x.encode('utf-8')
00131 length = len(_x)
00132 buff.write(struct.pack('<I%ss'%length, length, _x))
00133 _x = self
00134 buff.write(_struct_3I.pack(_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs))
00135 _x = self.goal.trajectory.header.frame_id
00136 length = len(_x)
00137 if python3 or type(_x) == unicode:
00138 _x = _x.encode('utf-8')
00139 length = len(_x)
00140 buff.write(struct.pack('<I%ss'%length, length, _x))
00141 length = len(self.goal.trajectory.joint_names)
00142 buff.write(_struct_I.pack(length))
00143 for val1 in self.goal.trajectory.joint_names:
00144 length = len(val1)
00145 if python3 or type(val1) == unicode:
00146 val1 = val1.encode('utf-8')
00147 length = len(val1)
00148 buff.write(struct.pack('<I%ss'%length, length, val1))
00149 length = len(self.goal.trajectory.points)
00150 buff.write(_struct_I.pack(length))
00151 for val1 in self.goal.trajectory.points:
00152 length = len(val1.positions)
00153 buff.write(_struct_I.pack(length))
00154 pattern = '<%sd'%length
00155 buff.write(struct.pack(pattern, *val1.positions))
00156 length = len(val1.velocities)
00157 buff.write(_struct_I.pack(length))
00158 pattern = '<%sd'%length
00159 buff.write(struct.pack(pattern, *val1.velocities))
00160 length = len(val1.accelerations)
00161 buff.write(_struct_I.pack(length))
00162 pattern = '<%sd'%length
00163 buff.write(struct.pack(pattern, *val1.accelerations))
00164 _v1 = val1.time_from_start
00165 _x = _v1
00166 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00167 buff.write(_struct_B.pack(self.goal.relative))
00168 except struct.error as se: self._check_types(se)
00169 except TypeError as te: self._check_types(te)
00170
00171 def deserialize(self, str):
00172 """
00173 unpack serialized message in str into this message instance
00174 :param str: byte array of serialized message, ``str``
00175 """
00176 try:
00177 if self.header is None:
00178 self.header = std_msgs.msg.Header()
00179 if self.goal_id is None:
00180 self.goal_id = actionlib_msgs.msg.GoalID()
00181 if self.goal is None:
00182 self.goal = nao_msgs.msg.JointTrajectoryGoal()
00183 end = 0
00184 _x = self
00185 start = end
00186 end += 12
00187 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00188 start = end
00189 end += 4
00190 (length,) = _struct_I.unpack(str[start:end])
00191 start = end
00192 end += length
00193 if python3:
00194 self.header.frame_id = str[start:end].decode('utf-8')
00195 else:
00196 self.header.frame_id = str[start:end]
00197 _x = self
00198 start = end
00199 end += 8
00200 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00201 start = end
00202 end += 4
00203 (length,) = _struct_I.unpack(str[start:end])
00204 start = end
00205 end += length
00206 if python3:
00207 self.goal_id.id = str[start:end].decode('utf-8')
00208 else:
00209 self.goal_id.id = str[start:end]
00210 _x = self
00211 start = end
00212 end += 12
00213 (_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00214 start = end
00215 end += 4
00216 (length,) = _struct_I.unpack(str[start:end])
00217 start = end
00218 end += length
00219 if python3:
00220 self.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00221 else:
00222 self.goal.trajectory.header.frame_id = str[start:end]
00223 start = end
00224 end += 4
00225 (length,) = _struct_I.unpack(str[start:end])
00226 self.goal.trajectory.joint_names = []
00227 for i in range(0, length):
00228 start = end
00229 end += 4
00230 (length,) = _struct_I.unpack(str[start:end])
00231 start = end
00232 end += length
00233 if python3:
00234 val1 = str[start:end].decode('utf-8')
00235 else:
00236 val1 = str[start:end]
00237 self.goal.trajectory.joint_names.append(val1)
00238 start = end
00239 end += 4
00240 (length,) = _struct_I.unpack(str[start:end])
00241 self.goal.trajectory.points = []
00242 for i in range(0, length):
00243 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00244 start = end
00245 end += 4
00246 (length,) = _struct_I.unpack(str[start:end])
00247 pattern = '<%sd'%length
00248 start = end
00249 end += struct.calcsize(pattern)
00250 val1.positions = struct.unpack(pattern, 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 val1.velocities = 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 val1.accelerations = struct.unpack(pattern, str[start:end])
00265 _v2 = val1.time_from_start
00266 _x = _v2
00267 start = end
00268 end += 8
00269 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00270 self.goal.trajectory.points.append(val1)
00271 start = end
00272 end += 1
00273 (self.goal.relative,) = _struct_B.unpack(str[start:end])
00274 return self
00275 except struct.error as e:
00276 raise genpy.DeserializationError(e)
00277
00278
00279 def serialize_numpy(self, buff, numpy):
00280 """
00281 serialize message with numpy array types into buffer
00282 :param buff: buffer, ``StringIO``
00283 :param numpy: numpy python module
00284 """
00285 try:
00286 _x = self
00287 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00288 _x = self.header.frame_id
00289 length = len(_x)
00290 if python3 or type(_x) == unicode:
00291 _x = _x.encode('utf-8')
00292 length = len(_x)
00293 buff.write(struct.pack('<I%ss'%length, length, _x))
00294 _x = self
00295 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00296 _x = self.goal_id.id
00297 length = len(_x)
00298 if python3 or type(_x) == unicode:
00299 _x = _x.encode('utf-8')
00300 length = len(_x)
00301 buff.write(struct.pack('<I%ss'%length, length, _x))
00302 _x = self
00303 buff.write(_struct_3I.pack(_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs))
00304 _x = self.goal.trajectory.header.frame_id
00305 length = len(_x)
00306 if python3 or type(_x) == unicode:
00307 _x = _x.encode('utf-8')
00308 length = len(_x)
00309 buff.write(struct.pack('<I%ss'%length, length, _x))
00310 length = len(self.goal.trajectory.joint_names)
00311 buff.write(_struct_I.pack(length))
00312 for val1 in self.goal.trajectory.joint_names:
00313 length = len(val1)
00314 if python3 or type(val1) == unicode:
00315 val1 = val1.encode('utf-8')
00316 length = len(val1)
00317 buff.write(struct.pack('<I%ss'%length, length, val1))
00318 length = len(self.goal.trajectory.points)
00319 buff.write(_struct_I.pack(length))
00320 for val1 in self.goal.trajectory.points:
00321 length = len(val1.positions)
00322 buff.write(_struct_I.pack(length))
00323 pattern = '<%sd'%length
00324 buff.write(val1.positions.tostring())
00325 length = len(val1.velocities)
00326 buff.write(_struct_I.pack(length))
00327 pattern = '<%sd'%length
00328 buff.write(val1.velocities.tostring())
00329 length = len(val1.accelerations)
00330 buff.write(_struct_I.pack(length))
00331 pattern = '<%sd'%length
00332 buff.write(val1.accelerations.tostring())
00333 _v3 = val1.time_from_start
00334 _x = _v3
00335 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00336 buff.write(_struct_B.pack(self.goal.relative))
00337 except struct.error as se: self._check_types(se)
00338 except TypeError as te: self._check_types(te)
00339
00340 def deserialize_numpy(self, str, numpy):
00341 """
00342 unpack serialized message in str into this message instance using numpy for array types
00343 :param str: byte array of serialized message, ``str``
00344 :param numpy: numpy python module
00345 """
00346 try:
00347 if self.header is None:
00348 self.header = std_msgs.msg.Header()
00349 if self.goal_id is None:
00350 self.goal_id = actionlib_msgs.msg.GoalID()
00351 if self.goal is None:
00352 self.goal = nao_msgs.msg.JointTrajectoryGoal()
00353 end = 0
00354 _x = self
00355 start = end
00356 end += 12
00357 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00358 start = end
00359 end += 4
00360 (length,) = _struct_I.unpack(str[start:end])
00361 start = end
00362 end += length
00363 if python3:
00364 self.header.frame_id = str[start:end].decode('utf-8')
00365 else:
00366 self.header.frame_id = str[start:end]
00367 _x = self
00368 start = end
00369 end += 8
00370 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00371 start = end
00372 end += 4
00373 (length,) = _struct_I.unpack(str[start:end])
00374 start = end
00375 end += length
00376 if python3:
00377 self.goal_id.id = str[start:end].decode('utf-8')
00378 else:
00379 self.goal_id.id = str[start:end]
00380 _x = self
00381 start = end
00382 end += 12
00383 (_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00384 start = end
00385 end += 4
00386 (length,) = _struct_I.unpack(str[start:end])
00387 start = end
00388 end += length
00389 if python3:
00390 self.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00391 else:
00392 self.goal.trajectory.header.frame_id = str[start:end]
00393 start = end
00394 end += 4
00395 (length,) = _struct_I.unpack(str[start:end])
00396 self.goal.trajectory.joint_names = []
00397 for i in range(0, length):
00398 start = end
00399 end += 4
00400 (length,) = _struct_I.unpack(str[start:end])
00401 start = end
00402 end += length
00403 if python3:
00404 val1 = str[start:end].decode('utf-8')
00405 else:
00406 val1 = str[start:end]
00407 self.goal.trajectory.joint_names.append(val1)
00408 start = end
00409 end += 4
00410 (length,) = _struct_I.unpack(str[start:end])
00411 self.goal.trajectory.points = []
00412 for i in range(0, length):
00413 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00414 start = end
00415 end += 4
00416 (length,) = _struct_I.unpack(str[start:end])
00417 pattern = '<%sd'%length
00418 start = end
00419 end += struct.calcsize(pattern)
00420 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00421 start = end
00422 end += 4
00423 (length,) = _struct_I.unpack(str[start:end])
00424 pattern = '<%sd'%length
00425 start = end
00426 end += struct.calcsize(pattern)
00427 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00428 start = end
00429 end += 4
00430 (length,) = _struct_I.unpack(str[start:end])
00431 pattern = '<%sd'%length
00432 start = end
00433 end += struct.calcsize(pattern)
00434 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00435 _v4 = val1.time_from_start
00436 _x = _v4
00437 start = end
00438 end += 8
00439 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00440 self.goal.trajectory.points.append(val1)
00441 start = end
00442 end += 1
00443 (self.goal.relative,) = _struct_B.unpack(str[start:end])
00444 return self
00445 except struct.error as e:
00446 raise genpy.DeserializationError(e)
00447
00448 _struct_I = genpy.struct_I
00449 _struct_3I = struct.Struct("<3I")
00450 _struct_B = struct.Struct("<B")
00451 _struct_2I = struct.Struct("<2I")
00452 _struct_2i = struct.Struct("<2i")