00001 """autogenerated by genpy from control_msgs/FollowJointTrajectoryAction.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 std_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import control_msgs.msg
00012
00013 class FollowJointTrajectoryAction(genpy.Message):
00014 _md5sum = "a1222b69ec4dcd1675e990ca2f8fe9be"
00015 _type = "control_msgs/FollowJointTrajectoryAction"
00016 _has_header = False
00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018
00019 FollowJointTrajectoryActionGoal action_goal
00020 FollowJointTrajectoryActionResult action_result
00021 FollowJointTrajectoryActionFeedback action_feedback
00022
00023 ================================================================================
00024 MSG: control_msgs/FollowJointTrajectoryActionGoal
00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00026
00027 Header header
00028 actionlib_msgs/GoalID goal_id
00029 FollowJointTrajectoryGoal goal
00030
00031 ================================================================================
00032 MSG: std_msgs/Header
00033 # Standard metadata for higher-level stamped data types.
00034 # This is generally used to communicate timestamped data
00035 # in a particular coordinate frame.
00036 #
00037 # sequence ID: consecutively increasing ID
00038 uint32 seq
00039 #Two-integer timestamp that is expressed as:
00040 # * stamp.secs: seconds (stamp_secs) since epoch
00041 # * stamp.nsecs: nanoseconds since stamp_secs
00042 # time-handling sugar is provided by the client library
00043 time stamp
00044 #Frame this data is associated with
00045 # 0: no frame
00046 # 1: global frame
00047 string frame_id
00048
00049 ================================================================================
00050 MSG: actionlib_msgs/GoalID
00051 # The stamp should store the time at which this goal was requested.
00052 # It is used by an action server when it tries to preempt all
00053 # goals that were requested before a certain time
00054 time stamp
00055
00056 # The id provides a way to associate feedback and
00057 # result message with specific goal requests. The id
00058 # specified must be unique.
00059 string id
00060
00061
00062 ================================================================================
00063 MSG: control_msgs/FollowJointTrajectoryGoal
00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00065 # The joint trajectory to follow
00066 trajectory_msgs/JointTrajectory trajectory
00067
00068 # Tolerances for the trajectory. If the measured joint values fall
00069 # outside the tolerances the trajectory goal is aborted. Any
00070 # tolerances that are not specified (by being omitted or set to 0) are
00071 # set to the defaults for the action server (often taken from the
00072 # parameter server).
00073
00074 # Tolerances applied to the joints as the trajectory is executed. If
00075 # violated, the goal aborts with error_code set to
00076 # PATH_TOLERANCE_VIOLATED.
00077 JointTolerance[] path_tolerance
00078
00079 # To report success, the joints must be within goal_tolerance of the
00080 # final trajectory value. The goal must be achieved by time the
00081 # trajectory ends plus goal_time_tolerance. (goal_time_tolerance
00082 # allows some leeway in time, so that the trajectory goal can still
00083 # succeed even if the joints reach the goal some time after the
00084 # precise end time of the trajectory).
00085 #
00086 # If the joints are not within goal_tolerance after "trajectory finish
00087 # time" + goal_time_tolerance, the goal aborts with error_code set to
00088 # GOAL_TOLERANCE_VIOLATED
00089 JointTolerance[] goal_tolerance
00090 duration goal_time_tolerance
00091
00092
00093 ================================================================================
00094 MSG: trajectory_msgs/JointTrajectory
00095 Header header
00096 string[] joint_names
00097 JointTrajectoryPoint[] points
00098 ================================================================================
00099 MSG: trajectory_msgs/JointTrajectoryPoint
00100 float64[] positions
00101 float64[] velocities
00102 float64[] accelerations
00103 duration time_from_start
00104 ================================================================================
00105 MSG: control_msgs/JointTolerance
00106 # The tolerances specify the amount the position, velocity, and
00107 # accelerations can vary from the setpoints. For example, in the case
00108 # of trajectory control, when the actual position varies beyond
00109 # (desired position + position tolerance), the trajectory goal may
00110 # abort.
00111 #
00112 # There are two special values for tolerances:
00113 # * 0 - The tolerance is unspecified and will remain at whatever the default is
00114 # * -1 - The tolerance is "erased". If there was a default, the joint will be
00115 # allowed to move without restriction.
00116
00117 string name
00118 float64 position # in radians or meters (for a revolute or prismatic joint, respectively)
00119 float64 velocity # in rad/sec or m/sec
00120 float64 acceleration # in rad/sec^2 or m/sec^2
00121
00122 ================================================================================
00123 MSG: control_msgs/FollowJointTrajectoryActionResult
00124 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00125
00126 Header header
00127 actionlib_msgs/GoalStatus status
00128 FollowJointTrajectoryResult result
00129
00130 ================================================================================
00131 MSG: actionlib_msgs/GoalStatus
00132 GoalID goal_id
00133 uint8 status
00134 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00135 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00136 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00137 # and has since completed its execution (Terminal State)
00138 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00139 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00140 # to some failure (Terminal State)
00141 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00142 # because the goal was unattainable or invalid (Terminal State)
00143 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00144 # and has not yet completed execution
00145 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00146 # but the action server has not yet confirmed that the goal is canceled
00147 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00148 # and was successfully cancelled (Terminal State)
00149 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00150 # sent over the wire by an action server
00151
00152 #Allow for the user to associate a string with GoalStatus for debugging
00153 string text
00154
00155
00156 ================================================================================
00157 MSG: control_msgs/FollowJointTrajectoryResult
00158 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00159 int32 error_code
00160 int32 SUCCESSFUL = 0
00161 int32 INVALID_GOAL = -1
00162 int32 INVALID_JOINTS = -2
00163 int32 OLD_HEADER_TIMESTAMP = -3
00164 int32 PATH_TOLERANCE_VIOLATED = -4
00165 int32 GOAL_TOLERANCE_VIOLATED = -5
00166
00167
00168 ================================================================================
00169 MSG: control_msgs/FollowJointTrajectoryActionFeedback
00170 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00171
00172 Header header
00173 actionlib_msgs/GoalStatus status
00174 FollowJointTrajectoryFeedback feedback
00175
00176 ================================================================================
00177 MSG: control_msgs/FollowJointTrajectoryFeedback
00178 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00179 Header header
00180 string[] joint_names
00181 trajectory_msgs/JointTrajectoryPoint desired
00182 trajectory_msgs/JointTrajectoryPoint actual
00183 trajectory_msgs/JointTrajectoryPoint error
00184
00185
00186 """
00187 __slots__ = ['action_goal','action_result','action_feedback']
00188 _slot_types = ['control_msgs/FollowJointTrajectoryActionGoal','control_msgs/FollowJointTrajectoryActionResult','control_msgs/FollowJointTrajectoryActionFeedback']
00189
00190 def __init__(self, *args, **kwds):
00191 """
00192 Constructor. Any message fields that are implicitly/explicitly
00193 set to None will be assigned a default value. The recommend
00194 use is keyword arguments as this is more robust to future message
00195 changes. You cannot mix in-order arguments and keyword arguments.
00196
00197 The available fields are:
00198 action_goal,action_result,action_feedback
00199
00200 :param args: complete set of field values, in .msg order
00201 :param kwds: use keyword arguments corresponding to message field names
00202 to set specific fields.
00203 """
00204 if args or kwds:
00205 super(FollowJointTrajectoryAction, self).__init__(*args, **kwds)
00206
00207 if self.action_goal is None:
00208 self.action_goal = control_msgs.msg.FollowJointTrajectoryActionGoal()
00209 if self.action_result is None:
00210 self.action_result = control_msgs.msg.FollowJointTrajectoryActionResult()
00211 if self.action_feedback is None:
00212 self.action_feedback = control_msgs.msg.FollowJointTrajectoryActionFeedback()
00213 else:
00214 self.action_goal = control_msgs.msg.FollowJointTrajectoryActionGoal()
00215 self.action_result = control_msgs.msg.FollowJointTrajectoryActionResult()
00216 self.action_feedback = control_msgs.msg.FollowJointTrajectoryActionFeedback()
00217
00218 def _get_types(self):
00219 """
00220 internal API method
00221 """
00222 return self._slot_types
00223
00224 def serialize(self, buff):
00225 """
00226 serialize message into buffer
00227 :param buff: buffer, ``StringIO``
00228 """
00229 try:
00230 _x = self
00231 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00232 _x = self.action_goal.header.frame_id
00233 length = len(_x)
00234 if python3 or type(_x) == unicode:
00235 _x = _x.encode('utf-8')
00236 length = len(_x)
00237 buff.write(struct.pack('<I%ss'%length, length, _x))
00238 _x = self
00239 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00240 _x = self.action_goal.goal_id.id
00241 length = len(_x)
00242 if python3 or type(_x) == unicode:
00243 _x = _x.encode('utf-8')
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 _x = self
00247 buff.write(_struct_3I.pack(_x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs))
00248 _x = self.action_goal.goal.trajectory.header.frame_id
00249 length = len(_x)
00250 if python3 or type(_x) == unicode:
00251 _x = _x.encode('utf-8')
00252 length = len(_x)
00253 buff.write(struct.pack('<I%ss'%length, length, _x))
00254 length = len(self.action_goal.goal.trajectory.joint_names)
00255 buff.write(_struct_I.pack(length))
00256 for val1 in self.action_goal.goal.trajectory.joint_names:
00257 length = len(val1)
00258 if python3 or type(val1) == unicode:
00259 val1 = val1.encode('utf-8')
00260 length = len(val1)
00261 buff.write(struct.pack('<I%ss'%length, length, val1))
00262 length = len(self.action_goal.goal.trajectory.points)
00263 buff.write(_struct_I.pack(length))
00264 for val1 in self.action_goal.goal.trajectory.points:
00265 length = len(val1.positions)
00266 buff.write(_struct_I.pack(length))
00267 pattern = '<%sd'%length
00268 buff.write(struct.pack(pattern, *val1.positions))
00269 length = len(val1.velocities)
00270 buff.write(_struct_I.pack(length))
00271 pattern = '<%sd'%length
00272 buff.write(struct.pack(pattern, *val1.velocities))
00273 length = len(val1.accelerations)
00274 buff.write(_struct_I.pack(length))
00275 pattern = '<%sd'%length
00276 buff.write(struct.pack(pattern, *val1.accelerations))
00277 _v1 = val1.time_from_start
00278 _x = _v1
00279 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00280 length = len(self.action_goal.goal.path_tolerance)
00281 buff.write(_struct_I.pack(length))
00282 for val1 in self.action_goal.goal.path_tolerance:
00283 _x = val1.name
00284 length = len(_x)
00285 if python3 or type(_x) == unicode:
00286 _x = _x.encode('utf-8')
00287 length = len(_x)
00288 buff.write(struct.pack('<I%ss'%length, length, _x))
00289 _x = val1
00290 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00291 length = len(self.action_goal.goal.goal_tolerance)
00292 buff.write(_struct_I.pack(length))
00293 for val1 in self.action_goal.goal.goal_tolerance:
00294 _x = val1.name
00295 length = len(_x)
00296 if python3 or type(_x) == unicode:
00297 _x = _x.encode('utf-8')
00298 length = len(_x)
00299 buff.write(struct.pack('<I%ss'%length, length, _x))
00300 _x = val1
00301 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00302 _x = self
00303 buff.write(_struct_2i3I.pack(_x.action_goal.goal.goal_time_tolerance.secs, _x.action_goal.goal.goal_time_tolerance.nsecs, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00304 _x = self.action_result.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 _x = self
00311 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00312 _x = self.action_result.status.goal_id.id
00313 length = len(_x)
00314 if python3 or type(_x) == unicode:
00315 _x = _x.encode('utf-8')
00316 length = len(_x)
00317 buff.write(struct.pack('<I%ss'%length, length, _x))
00318 buff.write(_struct_B.pack(self.action_result.status.status))
00319 _x = self.action_result.status.text
00320 length = len(_x)
00321 if python3 or type(_x) == unicode:
00322 _x = _x.encode('utf-8')
00323 length = len(_x)
00324 buff.write(struct.pack('<I%ss'%length, length, _x))
00325 _x = self
00326 buff.write(_struct_i3I.pack(_x.action_result.result.error_code, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00327 _x = self.action_feedback.header.frame_id
00328 length = len(_x)
00329 if python3 or type(_x) == unicode:
00330 _x = _x.encode('utf-8')
00331 length = len(_x)
00332 buff.write(struct.pack('<I%ss'%length, length, _x))
00333 _x = self
00334 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00335 _x = self.action_feedback.status.goal_id.id
00336 length = len(_x)
00337 if python3 or type(_x) == unicode:
00338 _x = _x.encode('utf-8')
00339 length = len(_x)
00340 buff.write(struct.pack('<I%ss'%length, length, _x))
00341 buff.write(_struct_B.pack(self.action_feedback.status.status))
00342 _x = self.action_feedback.status.text
00343 length = len(_x)
00344 if python3 or type(_x) == unicode:
00345 _x = _x.encode('utf-8')
00346 length = len(_x)
00347 buff.write(struct.pack('<I%ss'%length, length, _x))
00348 _x = self
00349 buff.write(_struct_3I.pack(_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs))
00350 _x = self.action_feedback.feedback.header.frame_id
00351 length = len(_x)
00352 if python3 or type(_x) == unicode:
00353 _x = _x.encode('utf-8')
00354 length = len(_x)
00355 buff.write(struct.pack('<I%ss'%length, length, _x))
00356 length = len(self.action_feedback.feedback.joint_names)
00357 buff.write(_struct_I.pack(length))
00358 for val1 in self.action_feedback.feedback.joint_names:
00359 length = len(val1)
00360 if python3 or type(val1) == unicode:
00361 val1 = val1.encode('utf-8')
00362 length = len(val1)
00363 buff.write(struct.pack('<I%ss'%length, length, val1))
00364 length = len(self.action_feedback.feedback.desired.positions)
00365 buff.write(_struct_I.pack(length))
00366 pattern = '<%sd'%length
00367 buff.write(struct.pack(pattern, *self.action_feedback.feedback.desired.positions))
00368 length = len(self.action_feedback.feedback.desired.velocities)
00369 buff.write(_struct_I.pack(length))
00370 pattern = '<%sd'%length
00371 buff.write(struct.pack(pattern, *self.action_feedback.feedback.desired.velocities))
00372 length = len(self.action_feedback.feedback.desired.accelerations)
00373 buff.write(_struct_I.pack(length))
00374 pattern = '<%sd'%length
00375 buff.write(struct.pack(pattern, *self.action_feedback.feedback.desired.accelerations))
00376 _x = self
00377 buff.write(_struct_2i.pack(_x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs))
00378 length = len(self.action_feedback.feedback.actual.positions)
00379 buff.write(_struct_I.pack(length))
00380 pattern = '<%sd'%length
00381 buff.write(struct.pack(pattern, *self.action_feedback.feedback.actual.positions))
00382 length = len(self.action_feedback.feedback.actual.velocities)
00383 buff.write(_struct_I.pack(length))
00384 pattern = '<%sd'%length
00385 buff.write(struct.pack(pattern, *self.action_feedback.feedback.actual.velocities))
00386 length = len(self.action_feedback.feedback.actual.accelerations)
00387 buff.write(_struct_I.pack(length))
00388 pattern = '<%sd'%length
00389 buff.write(struct.pack(pattern, *self.action_feedback.feedback.actual.accelerations))
00390 _x = self
00391 buff.write(_struct_2i.pack(_x.action_feedback.feedback.actual.time_from_start.secs, _x.action_feedback.feedback.actual.time_from_start.nsecs))
00392 length = len(self.action_feedback.feedback.error.positions)
00393 buff.write(_struct_I.pack(length))
00394 pattern = '<%sd'%length
00395 buff.write(struct.pack(pattern, *self.action_feedback.feedback.error.positions))
00396 length = len(self.action_feedback.feedback.error.velocities)
00397 buff.write(_struct_I.pack(length))
00398 pattern = '<%sd'%length
00399 buff.write(struct.pack(pattern, *self.action_feedback.feedback.error.velocities))
00400 length = len(self.action_feedback.feedback.error.accelerations)
00401 buff.write(_struct_I.pack(length))
00402 pattern = '<%sd'%length
00403 buff.write(struct.pack(pattern, *self.action_feedback.feedback.error.accelerations))
00404 _x = self
00405 buff.write(_struct_2i.pack(_x.action_feedback.feedback.error.time_from_start.secs, _x.action_feedback.feedback.error.time_from_start.nsecs))
00406 except struct.error as se: self._check_types(se)
00407 except TypeError as te: self._check_types(te)
00408
00409 def deserialize(self, str):
00410 """
00411 unpack serialized message in str into this message instance
00412 :param str: byte array of serialized message, ``str``
00413 """
00414 try:
00415 if self.action_goal is None:
00416 self.action_goal = control_msgs.msg.FollowJointTrajectoryActionGoal()
00417 if self.action_result is None:
00418 self.action_result = control_msgs.msg.FollowJointTrajectoryActionResult()
00419 if self.action_feedback is None:
00420 self.action_feedback = control_msgs.msg.FollowJointTrajectoryActionFeedback()
00421 end = 0
00422 _x = self
00423 start = end
00424 end += 12
00425 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00426 start = end
00427 end += 4
00428 (length,) = _struct_I.unpack(str[start:end])
00429 start = end
00430 end += length
00431 if python3:
00432 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00433 else:
00434 self.action_goal.header.frame_id = str[start:end]
00435 _x = self
00436 start = end
00437 end += 8
00438 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00439 start = end
00440 end += 4
00441 (length,) = _struct_I.unpack(str[start:end])
00442 start = end
00443 end += length
00444 if python3:
00445 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00446 else:
00447 self.action_goal.goal_id.id = str[start:end]
00448 _x = self
00449 start = end
00450 end += 12
00451 (_x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00452 start = end
00453 end += 4
00454 (length,) = _struct_I.unpack(str[start:end])
00455 start = end
00456 end += length
00457 if python3:
00458 self.action_goal.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00459 else:
00460 self.action_goal.goal.trajectory.header.frame_id = str[start:end]
00461 start = end
00462 end += 4
00463 (length,) = _struct_I.unpack(str[start:end])
00464 self.action_goal.goal.trajectory.joint_names = []
00465 for i in range(0, length):
00466 start = end
00467 end += 4
00468 (length,) = _struct_I.unpack(str[start:end])
00469 start = end
00470 end += length
00471 if python3:
00472 val1 = str[start:end].decode('utf-8')
00473 else:
00474 val1 = str[start:end]
00475 self.action_goal.goal.trajectory.joint_names.append(val1)
00476 start = end
00477 end += 4
00478 (length,) = _struct_I.unpack(str[start:end])
00479 self.action_goal.goal.trajectory.points = []
00480 for i in range(0, length):
00481 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00482 start = end
00483 end += 4
00484 (length,) = _struct_I.unpack(str[start:end])
00485 pattern = '<%sd'%length
00486 start = end
00487 end += struct.calcsize(pattern)
00488 val1.positions = struct.unpack(pattern, str[start:end])
00489 start = end
00490 end += 4
00491 (length,) = _struct_I.unpack(str[start:end])
00492 pattern = '<%sd'%length
00493 start = end
00494 end += struct.calcsize(pattern)
00495 val1.velocities = struct.unpack(pattern, str[start:end])
00496 start = end
00497 end += 4
00498 (length,) = _struct_I.unpack(str[start:end])
00499 pattern = '<%sd'%length
00500 start = end
00501 end += struct.calcsize(pattern)
00502 val1.accelerations = struct.unpack(pattern, str[start:end])
00503 _v2 = val1.time_from_start
00504 _x = _v2
00505 start = end
00506 end += 8
00507 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00508 self.action_goal.goal.trajectory.points.append(val1)
00509 start = end
00510 end += 4
00511 (length,) = _struct_I.unpack(str[start:end])
00512 self.action_goal.goal.path_tolerance = []
00513 for i in range(0, length):
00514 val1 = control_msgs.msg.JointTolerance()
00515 start = end
00516 end += 4
00517 (length,) = _struct_I.unpack(str[start:end])
00518 start = end
00519 end += length
00520 if python3:
00521 val1.name = str[start:end].decode('utf-8')
00522 else:
00523 val1.name = str[start:end]
00524 _x = val1
00525 start = end
00526 end += 24
00527 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
00528 self.action_goal.goal.path_tolerance.append(val1)
00529 start = end
00530 end += 4
00531 (length,) = _struct_I.unpack(str[start:end])
00532 self.action_goal.goal.goal_tolerance = []
00533 for i in range(0, length):
00534 val1 = control_msgs.msg.JointTolerance()
00535 start = end
00536 end += 4
00537 (length,) = _struct_I.unpack(str[start:end])
00538 start = end
00539 end += length
00540 if python3:
00541 val1.name = str[start:end].decode('utf-8')
00542 else:
00543 val1.name = str[start:end]
00544 _x = val1
00545 start = end
00546 end += 24
00547 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
00548 self.action_goal.goal.goal_tolerance.append(val1)
00549 _x = self
00550 start = end
00551 end += 20
00552 (_x.action_goal.goal.goal_time_tolerance.secs, _x.action_goal.goal.goal_time_tolerance.nsecs, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_2i3I.unpack(str[start:end])
00553 start = end
00554 end += 4
00555 (length,) = _struct_I.unpack(str[start:end])
00556 start = end
00557 end += length
00558 if python3:
00559 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00560 else:
00561 self.action_result.header.frame_id = str[start:end]
00562 _x = self
00563 start = end
00564 end += 8
00565 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00566 start = end
00567 end += 4
00568 (length,) = _struct_I.unpack(str[start:end])
00569 start = end
00570 end += length
00571 if python3:
00572 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00573 else:
00574 self.action_result.status.goal_id.id = str[start:end]
00575 start = end
00576 end += 1
00577 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 start = end
00582 end += length
00583 if python3:
00584 self.action_result.status.text = str[start:end].decode('utf-8')
00585 else:
00586 self.action_result.status.text = str[start:end]
00587 _x = self
00588 start = end
00589 end += 16
00590 (_x.action_result.result.error_code, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00591 start = end
00592 end += 4
00593 (length,) = _struct_I.unpack(str[start:end])
00594 start = end
00595 end += length
00596 if python3:
00597 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00598 else:
00599 self.action_feedback.header.frame_id = str[start:end]
00600 _x = self
00601 start = end
00602 end += 8
00603 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00604 start = end
00605 end += 4
00606 (length,) = _struct_I.unpack(str[start:end])
00607 start = end
00608 end += length
00609 if python3:
00610 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00611 else:
00612 self.action_feedback.status.goal_id.id = str[start:end]
00613 start = end
00614 end += 1
00615 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00616 start = end
00617 end += 4
00618 (length,) = _struct_I.unpack(str[start:end])
00619 start = end
00620 end += length
00621 if python3:
00622 self.action_feedback.status.text = str[start:end].decode('utf-8')
00623 else:
00624 self.action_feedback.status.text = str[start:end]
00625 _x = self
00626 start = end
00627 end += 12
00628 (_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00629 start = end
00630 end += 4
00631 (length,) = _struct_I.unpack(str[start:end])
00632 start = end
00633 end += length
00634 if python3:
00635 self.action_feedback.feedback.header.frame_id = str[start:end].decode('utf-8')
00636 else:
00637 self.action_feedback.feedback.header.frame_id = str[start:end]
00638 start = end
00639 end += 4
00640 (length,) = _struct_I.unpack(str[start:end])
00641 self.action_feedback.feedback.joint_names = []
00642 for i in range(0, length):
00643 start = end
00644 end += 4
00645 (length,) = _struct_I.unpack(str[start:end])
00646 start = end
00647 end += length
00648 if python3:
00649 val1 = str[start:end].decode('utf-8')
00650 else:
00651 val1 = str[start:end]
00652 self.action_feedback.feedback.joint_names.append(val1)
00653 start = end
00654 end += 4
00655 (length,) = _struct_I.unpack(str[start:end])
00656 pattern = '<%sd'%length
00657 start = end
00658 end += struct.calcsize(pattern)
00659 self.action_feedback.feedback.desired.positions = struct.unpack(pattern, str[start:end])
00660 start = end
00661 end += 4
00662 (length,) = _struct_I.unpack(str[start:end])
00663 pattern = '<%sd'%length
00664 start = end
00665 end += struct.calcsize(pattern)
00666 self.action_feedback.feedback.desired.velocities = struct.unpack(pattern, str[start:end])
00667 start = end
00668 end += 4
00669 (length,) = _struct_I.unpack(str[start:end])
00670 pattern = '<%sd'%length
00671 start = end
00672 end += struct.calcsize(pattern)
00673 self.action_feedback.feedback.desired.accelerations = struct.unpack(pattern, str[start:end])
00674 _x = self
00675 start = end
00676 end += 8
00677 (_x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00678 start = end
00679 end += 4
00680 (length,) = _struct_I.unpack(str[start:end])
00681 pattern = '<%sd'%length
00682 start = end
00683 end += struct.calcsize(pattern)
00684 self.action_feedback.feedback.actual.positions = struct.unpack(pattern, str[start:end])
00685 start = end
00686 end += 4
00687 (length,) = _struct_I.unpack(str[start:end])
00688 pattern = '<%sd'%length
00689 start = end
00690 end += struct.calcsize(pattern)
00691 self.action_feedback.feedback.actual.velocities = struct.unpack(pattern, str[start:end])
00692 start = end
00693 end += 4
00694 (length,) = _struct_I.unpack(str[start:end])
00695 pattern = '<%sd'%length
00696 start = end
00697 end += struct.calcsize(pattern)
00698 self.action_feedback.feedback.actual.accelerations = struct.unpack(pattern, str[start:end])
00699 _x = self
00700 start = end
00701 end += 8
00702 (_x.action_feedback.feedback.actual.time_from_start.secs, _x.action_feedback.feedback.actual.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00703 start = end
00704 end += 4
00705 (length,) = _struct_I.unpack(str[start:end])
00706 pattern = '<%sd'%length
00707 start = end
00708 end += struct.calcsize(pattern)
00709 self.action_feedback.feedback.error.positions = struct.unpack(pattern, str[start:end])
00710 start = end
00711 end += 4
00712 (length,) = _struct_I.unpack(str[start:end])
00713 pattern = '<%sd'%length
00714 start = end
00715 end += struct.calcsize(pattern)
00716 self.action_feedback.feedback.error.velocities = struct.unpack(pattern, str[start:end])
00717 start = end
00718 end += 4
00719 (length,) = _struct_I.unpack(str[start:end])
00720 pattern = '<%sd'%length
00721 start = end
00722 end += struct.calcsize(pattern)
00723 self.action_feedback.feedback.error.accelerations = struct.unpack(pattern, str[start:end])
00724 _x = self
00725 start = end
00726 end += 8
00727 (_x.action_feedback.feedback.error.time_from_start.secs, _x.action_feedback.feedback.error.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00728 return self
00729 except struct.error as e:
00730 raise genpy.DeserializationError(e)
00731
00732
00733 def serialize_numpy(self, buff, numpy):
00734 """
00735 serialize message with numpy array types into buffer
00736 :param buff: buffer, ``StringIO``
00737 :param numpy: numpy python module
00738 """
00739 try:
00740 _x = self
00741 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00742 _x = self.action_goal.header.frame_id
00743 length = len(_x)
00744 if python3 or type(_x) == unicode:
00745 _x = _x.encode('utf-8')
00746 length = len(_x)
00747 buff.write(struct.pack('<I%ss'%length, length, _x))
00748 _x = self
00749 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00750 _x = self.action_goal.goal_id.id
00751 length = len(_x)
00752 if python3 or type(_x) == unicode:
00753 _x = _x.encode('utf-8')
00754 length = len(_x)
00755 buff.write(struct.pack('<I%ss'%length, length, _x))
00756 _x = self
00757 buff.write(_struct_3I.pack(_x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs))
00758 _x = self.action_goal.goal.trajectory.header.frame_id
00759 length = len(_x)
00760 if python3 or type(_x) == unicode:
00761 _x = _x.encode('utf-8')
00762 length = len(_x)
00763 buff.write(struct.pack('<I%ss'%length, length, _x))
00764 length = len(self.action_goal.goal.trajectory.joint_names)
00765 buff.write(_struct_I.pack(length))
00766 for val1 in self.action_goal.goal.trajectory.joint_names:
00767 length = len(val1)
00768 if python3 or type(val1) == unicode:
00769 val1 = val1.encode('utf-8')
00770 length = len(val1)
00771 buff.write(struct.pack('<I%ss'%length, length, val1))
00772 length = len(self.action_goal.goal.trajectory.points)
00773 buff.write(_struct_I.pack(length))
00774 for val1 in self.action_goal.goal.trajectory.points:
00775 length = len(val1.positions)
00776 buff.write(_struct_I.pack(length))
00777 pattern = '<%sd'%length
00778 buff.write(val1.positions.tostring())
00779 length = len(val1.velocities)
00780 buff.write(_struct_I.pack(length))
00781 pattern = '<%sd'%length
00782 buff.write(val1.velocities.tostring())
00783 length = len(val1.accelerations)
00784 buff.write(_struct_I.pack(length))
00785 pattern = '<%sd'%length
00786 buff.write(val1.accelerations.tostring())
00787 _v3 = val1.time_from_start
00788 _x = _v3
00789 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00790 length = len(self.action_goal.goal.path_tolerance)
00791 buff.write(_struct_I.pack(length))
00792 for val1 in self.action_goal.goal.path_tolerance:
00793 _x = val1.name
00794 length = len(_x)
00795 if python3 or type(_x) == unicode:
00796 _x = _x.encode('utf-8')
00797 length = len(_x)
00798 buff.write(struct.pack('<I%ss'%length, length, _x))
00799 _x = val1
00800 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00801 length = len(self.action_goal.goal.goal_tolerance)
00802 buff.write(_struct_I.pack(length))
00803 for val1 in self.action_goal.goal.goal_tolerance:
00804 _x = val1.name
00805 length = len(_x)
00806 if python3 or type(_x) == unicode:
00807 _x = _x.encode('utf-8')
00808 length = len(_x)
00809 buff.write(struct.pack('<I%ss'%length, length, _x))
00810 _x = val1
00811 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00812 _x = self
00813 buff.write(_struct_2i3I.pack(_x.action_goal.goal.goal_time_tolerance.secs, _x.action_goal.goal.goal_time_tolerance.nsecs, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00814 _x = self.action_result.header.frame_id
00815 length = len(_x)
00816 if python3 or type(_x) == unicode:
00817 _x = _x.encode('utf-8')
00818 length = len(_x)
00819 buff.write(struct.pack('<I%ss'%length, length, _x))
00820 _x = self
00821 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00822 _x = self.action_result.status.goal_id.id
00823 length = len(_x)
00824 if python3 or type(_x) == unicode:
00825 _x = _x.encode('utf-8')
00826 length = len(_x)
00827 buff.write(struct.pack('<I%ss'%length, length, _x))
00828 buff.write(_struct_B.pack(self.action_result.status.status))
00829 _x = self.action_result.status.text
00830 length = len(_x)
00831 if python3 or type(_x) == unicode:
00832 _x = _x.encode('utf-8')
00833 length = len(_x)
00834 buff.write(struct.pack('<I%ss'%length, length, _x))
00835 _x = self
00836 buff.write(_struct_i3I.pack(_x.action_result.result.error_code, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00837 _x = self.action_feedback.header.frame_id
00838 length = len(_x)
00839 if python3 or type(_x) == unicode:
00840 _x = _x.encode('utf-8')
00841 length = len(_x)
00842 buff.write(struct.pack('<I%ss'%length, length, _x))
00843 _x = self
00844 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00845 _x = self.action_feedback.status.goal_id.id
00846 length = len(_x)
00847 if python3 or type(_x) == unicode:
00848 _x = _x.encode('utf-8')
00849 length = len(_x)
00850 buff.write(struct.pack('<I%ss'%length, length, _x))
00851 buff.write(_struct_B.pack(self.action_feedback.status.status))
00852 _x = self.action_feedback.status.text
00853 length = len(_x)
00854 if python3 or type(_x) == unicode:
00855 _x = _x.encode('utf-8')
00856 length = len(_x)
00857 buff.write(struct.pack('<I%ss'%length, length, _x))
00858 _x = self
00859 buff.write(_struct_3I.pack(_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs))
00860 _x = self.action_feedback.feedback.header.frame_id
00861 length = len(_x)
00862 if python3 or type(_x) == unicode:
00863 _x = _x.encode('utf-8')
00864 length = len(_x)
00865 buff.write(struct.pack('<I%ss'%length, length, _x))
00866 length = len(self.action_feedback.feedback.joint_names)
00867 buff.write(_struct_I.pack(length))
00868 for val1 in self.action_feedback.feedback.joint_names:
00869 length = len(val1)
00870 if python3 or type(val1) == unicode:
00871 val1 = val1.encode('utf-8')
00872 length = len(val1)
00873 buff.write(struct.pack('<I%ss'%length, length, val1))
00874 length = len(self.action_feedback.feedback.desired.positions)
00875 buff.write(_struct_I.pack(length))
00876 pattern = '<%sd'%length
00877 buff.write(self.action_feedback.feedback.desired.positions.tostring())
00878 length = len(self.action_feedback.feedback.desired.velocities)
00879 buff.write(_struct_I.pack(length))
00880 pattern = '<%sd'%length
00881 buff.write(self.action_feedback.feedback.desired.velocities.tostring())
00882 length = len(self.action_feedback.feedback.desired.accelerations)
00883 buff.write(_struct_I.pack(length))
00884 pattern = '<%sd'%length
00885 buff.write(self.action_feedback.feedback.desired.accelerations.tostring())
00886 _x = self
00887 buff.write(_struct_2i.pack(_x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs))
00888 length = len(self.action_feedback.feedback.actual.positions)
00889 buff.write(_struct_I.pack(length))
00890 pattern = '<%sd'%length
00891 buff.write(self.action_feedback.feedback.actual.positions.tostring())
00892 length = len(self.action_feedback.feedback.actual.velocities)
00893 buff.write(_struct_I.pack(length))
00894 pattern = '<%sd'%length
00895 buff.write(self.action_feedback.feedback.actual.velocities.tostring())
00896 length = len(self.action_feedback.feedback.actual.accelerations)
00897 buff.write(_struct_I.pack(length))
00898 pattern = '<%sd'%length
00899 buff.write(self.action_feedback.feedback.actual.accelerations.tostring())
00900 _x = self
00901 buff.write(_struct_2i.pack(_x.action_feedback.feedback.actual.time_from_start.secs, _x.action_feedback.feedback.actual.time_from_start.nsecs))
00902 length = len(self.action_feedback.feedback.error.positions)
00903 buff.write(_struct_I.pack(length))
00904 pattern = '<%sd'%length
00905 buff.write(self.action_feedback.feedback.error.positions.tostring())
00906 length = len(self.action_feedback.feedback.error.velocities)
00907 buff.write(_struct_I.pack(length))
00908 pattern = '<%sd'%length
00909 buff.write(self.action_feedback.feedback.error.velocities.tostring())
00910 length = len(self.action_feedback.feedback.error.accelerations)
00911 buff.write(_struct_I.pack(length))
00912 pattern = '<%sd'%length
00913 buff.write(self.action_feedback.feedback.error.accelerations.tostring())
00914 _x = self
00915 buff.write(_struct_2i.pack(_x.action_feedback.feedback.error.time_from_start.secs, _x.action_feedback.feedback.error.time_from_start.nsecs))
00916 except struct.error as se: self._check_types(se)
00917 except TypeError as te: self._check_types(te)
00918
00919 def deserialize_numpy(self, str, numpy):
00920 """
00921 unpack serialized message in str into this message instance using numpy for array types
00922 :param str: byte array of serialized message, ``str``
00923 :param numpy: numpy python module
00924 """
00925 try:
00926 if self.action_goal is None:
00927 self.action_goal = control_msgs.msg.FollowJointTrajectoryActionGoal()
00928 if self.action_result is None:
00929 self.action_result = control_msgs.msg.FollowJointTrajectoryActionResult()
00930 if self.action_feedback is None:
00931 self.action_feedback = control_msgs.msg.FollowJointTrajectoryActionFeedback()
00932 end = 0
00933 _x = self
00934 start = end
00935 end += 12
00936 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00937 start = end
00938 end += 4
00939 (length,) = _struct_I.unpack(str[start:end])
00940 start = end
00941 end += length
00942 if python3:
00943 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00944 else:
00945 self.action_goal.header.frame_id = str[start:end]
00946 _x = self
00947 start = end
00948 end += 8
00949 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00950 start = end
00951 end += 4
00952 (length,) = _struct_I.unpack(str[start:end])
00953 start = end
00954 end += length
00955 if python3:
00956 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00957 else:
00958 self.action_goal.goal_id.id = str[start:end]
00959 _x = self
00960 start = end
00961 end += 12
00962 (_x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00963 start = end
00964 end += 4
00965 (length,) = _struct_I.unpack(str[start:end])
00966 start = end
00967 end += length
00968 if python3:
00969 self.action_goal.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00970 else:
00971 self.action_goal.goal.trajectory.header.frame_id = str[start:end]
00972 start = end
00973 end += 4
00974 (length,) = _struct_I.unpack(str[start:end])
00975 self.action_goal.goal.trajectory.joint_names = []
00976 for i in range(0, length):
00977 start = end
00978 end += 4
00979 (length,) = _struct_I.unpack(str[start:end])
00980 start = end
00981 end += length
00982 if python3:
00983 val1 = str[start:end].decode('utf-8')
00984 else:
00985 val1 = str[start:end]
00986 self.action_goal.goal.trajectory.joint_names.append(val1)
00987 start = end
00988 end += 4
00989 (length,) = _struct_I.unpack(str[start:end])
00990 self.action_goal.goal.trajectory.points = []
00991 for i in range(0, length):
00992 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00993 start = end
00994 end += 4
00995 (length,) = _struct_I.unpack(str[start:end])
00996 pattern = '<%sd'%length
00997 start = end
00998 end += struct.calcsize(pattern)
00999 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01000 start = end
01001 end += 4
01002 (length,) = _struct_I.unpack(str[start:end])
01003 pattern = '<%sd'%length
01004 start = end
01005 end += struct.calcsize(pattern)
01006 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01007 start = end
01008 end += 4
01009 (length,) = _struct_I.unpack(str[start:end])
01010 pattern = '<%sd'%length
01011 start = end
01012 end += struct.calcsize(pattern)
01013 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01014 _v4 = val1.time_from_start
01015 _x = _v4
01016 start = end
01017 end += 8
01018 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
01019 self.action_goal.goal.trajectory.points.append(val1)
01020 start = end
01021 end += 4
01022 (length,) = _struct_I.unpack(str[start:end])
01023 self.action_goal.goal.path_tolerance = []
01024 for i in range(0, length):
01025 val1 = control_msgs.msg.JointTolerance()
01026 start = end
01027 end += 4
01028 (length,) = _struct_I.unpack(str[start:end])
01029 start = end
01030 end += length
01031 if python3:
01032 val1.name = str[start:end].decode('utf-8')
01033 else:
01034 val1.name = str[start:end]
01035 _x = val1
01036 start = end
01037 end += 24
01038 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
01039 self.action_goal.goal.path_tolerance.append(val1)
01040 start = end
01041 end += 4
01042 (length,) = _struct_I.unpack(str[start:end])
01043 self.action_goal.goal.goal_tolerance = []
01044 for i in range(0, length):
01045 val1 = control_msgs.msg.JointTolerance()
01046 start = end
01047 end += 4
01048 (length,) = _struct_I.unpack(str[start:end])
01049 start = end
01050 end += length
01051 if python3:
01052 val1.name = str[start:end].decode('utf-8')
01053 else:
01054 val1.name = str[start:end]
01055 _x = val1
01056 start = end
01057 end += 24
01058 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
01059 self.action_goal.goal.goal_tolerance.append(val1)
01060 _x = self
01061 start = end
01062 end += 20
01063 (_x.action_goal.goal.goal_time_tolerance.secs, _x.action_goal.goal.goal_time_tolerance.nsecs, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_2i3I.unpack(str[start:end])
01064 start = end
01065 end += 4
01066 (length,) = _struct_I.unpack(str[start:end])
01067 start = end
01068 end += length
01069 if python3:
01070 self.action_result.header.frame_id = str[start:end].decode('utf-8')
01071 else:
01072 self.action_result.header.frame_id = str[start:end]
01073 _x = self
01074 start = end
01075 end += 8
01076 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01077 start = end
01078 end += 4
01079 (length,) = _struct_I.unpack(str[start:end])
01080 start = end
01081 end += length
01082 if python3:
01083 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01084 else:
01085 self.action_result.status.goal_id.id = str[start:end]
01086 start = end
01087 end += 1
01088 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01089 start = end
01090 end += 4
01091 (length,) = _struct_I.unpack(str[start:end])
01092 start = end
01093 end += length
01094 if python3:
01095 self.action_result.status.text = str[start:end].decode('utf-8')
01096 else:
01097 self.action_result.status.text = str[start:end]
01098 _x = self
01099 start = end
01100 end += 16
01101 (_x.action_result.result.error_code, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
01102 start = end
01103 end += 4
01104 (length,) = _struct_I.unpack(str[start:end])
01105 start = end
01106 end += length
01107 if python3:
01108 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01109 else:
01110 self.action_feedback.header.frame_id = str[start:end]
01111 _x = self
01112 start = end
01113 end += 8
01114 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01115 start = end
01116 end += 4
01117 (length,) = _struct_I.unpack(str[start:end])
01118 start = end
01119 end += length
01120 if python3:
01121 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01122 else:
01123 self.action_feedback.status.goal_id.id = str[start:end]
01124 start = end
01125 end += 1
01126 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01127 start = end
01128 end += 4
01129 (length,) = _struct_I.unpack(str[start:end])
01130 start = end
01131 end += length
01132 if python3:
01133 self.action_feedback.status.text = str[start:end].decode('utf-8')
01134 else:
01135 self.action_feedback.status.text = str[start:end]
01136 _x = self
01137 start = end
01138 end += 12
01139 (_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01140 start = end
01141 end += 4
01142 (length,) = _struct_I.unpack(str[start:end])
01143 start = end
01144 end += length
01145 if python3:
01146 self.action_feedback.feedback.header.frame_id = str[start:end].decode('utf-8')
01147 else:
01148 self.action_feedback.feedback.header.frame_id = str[start:end]
01149 start = end
01150 end += 4
01151 (length,) = _struct_I.unpack(str[start:end])
01152 self.action_feedback.feedback.joint_names = []
01153 for i in range(0, length):
01154 start = end
01155 end += 4
01156 (length,) = _struct_I.unpack(str[start:end])
01157 start = end
01158 end += length
01159 if python3:
01160 val1 = str[start:end].decode('utf-8')
01161 else:
01162 val1 = str[start:end]
01163 self.action_feedback.feedback.joint_names.append(val1)
01164 start = end
01165 end += 4
01166 (length,) = _struct_I.unpack(str[start:end])
01167 pattern = '<%sd'%length
01168 start = end
01169 end += struct.calcsize(pattern)
01170 self.action_feedback.feedback.desired.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01171 start = end
01172 end += 4
01173 (length,) = _struct_I.unpack(str[start:end])
01174 pattern = '<%sd'%length
01175 start = end
01176 end += struct.calcsize(pattern)
01177 self.action_feedback.feedback.desired.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01178 start = end
01179 end += 4
01180 (length,) = _struct_I.unpack(str[start:end])
01181 pattern = '<%sd'%length
01182 start = end
01183 end += struct.calcsize(pattern)
01184 self.action_feedback.feedback.desired.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01185 _x = self
01186 start = end
01187 end += 8
01188 (_x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
01189 start = end
01190 end += 4
01191 (length,) = _struct_I.unpack(str[start:end])
01192 pattern = '<%sd'%length
01193 start = end
01194 end += struct.calcsize(pattern)
01195 self.action_feedback.feedback.actual.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01196 start = end
01197 end += 4
01198 (length,) = _struct_I.unpack(str[start:end])
01199 pattern = '<%sd'%length
01200 start = end
01201 end += struct.calcsize(pattern)
01202 self.action_feedback.feedback.actual.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01203 start = end
01204 end += 4
01205 (length,) = _struct_I.unpack(str[start:end])
01206 pattern = '<%sd'%length
01207 start = end
01208 end += struct.calcsize(pattern)
01209 self.action_feedback.feedback.actual.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01210 _x = self
01211 start = end
01212 end += 8
01213 (_x.action_feedback.feedback.actual.time_from_start.secs, _x.action_feedback.feedback.actual.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
01214 start = end
01215 end += 4
01216 (length,) = _struct_I.unpack(str[start:end])
01217 pattern = '<%sd'%length
01218 start = end
01219 end += struct.calcsize(pattern)
01220 self.action_feedback.feedback.error.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01221 start = end
01222 end += 4
01223 (length,) = _struct_I.unpack(str[start:end])
01224 pattern = '<%sd'%length
01225 start = end
01226 end += struct.calcsize(pattern)
01227 self.action_feedback.feedback.error.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01228 start = end
01229 end += 4
01230 (length,) = _struct_I.unpack(str[start:end])
01231 pattern = '<%sd'%length
01232 start = end
01233 end += struct.calcsize(pattern)
01234 self.action_feedback.feedback.error.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01235 _x = self
01236 start = end
01237 end += 8
01238 (_x.action_feedback.feedback.error.time_from_start.secs, _x.action_feedback.feedback.error.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
01239 return self
01240 except struct.error as e:
01241 raise genpy.DeserializationError(e)
01242
01243 _struct_I = genpy.struct_I
01244 _struct_B = struct.Struct("<B")
01245 _struct_2i3I = struct.Struct("<2i3I")
01246 _struct_i3I = struct.Struct("<i3I")
01247 _struct_2i = struct.Struct("<2i")
01248 _struct_3I = struct.Struct("<3I")
01249 _struct_2I = struct.Struct("<2I")
01250 _struct_3d = struct.Struct("<3d")