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