00001 """autogenerated by genpy from control_msgs/FollowJointTrajectoryActionGoal.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 control_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import std_msgs.msg
00012
00013 class FollowJointTrajectoryActionGoal(genpy.Message):
00014 _md5sum = "8f3e00277a7b5b7c60e1ac5be35ddfa2"
00015 _type = "control_msgs/FollowJointTrajectoryActionGoal"
00016 _has_header = True
00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018
00019 Header header
00020 actionlib_msgs/GoalID goal_id
00021 FollowJointTrajectoryGoal goal
00022
00023 ================================================================================
00024 MSG: std_msgs/Header
00025 # Standard metadata for higher-level stamped data types.
00026 # This is generally used to communicate timestamped data
00027 # in a particular coordinate frame.
00028 #
00029 # sequence ID: consecutively increasing ID
00030 uint32 seq
00031 #Two-integer timestamp that is expressed as:
00032 # * stamp.secs: seconds (stamp_secs) since epoch
00033 # * stamp.nsecs: nanoseconds since stamp_secs
00034 # time-handling sugar is provided by the client library
00035 time stamp
00036 #Frame this data is associated with
00037 # 0: no frame
00038 # 1: global frame
00039 string frame_id
00040
00041 ================================================================================
00042 MSG: actionlib_msgs/GoalID
00043 # The stamp should store the time at which this goal was requested.
00044 # It is used by an action server when it tries to preempt all
00045 # goals that were requested before a certain time
00046 time stamp
00047
00048 # The id provides a way to associate feedback and
00049 # result message with specific goal requests. The id
00050 # specified must be unique.
00051 string id
00052
00053
00054 ================================================================================
00055 MSG: control_msgs/FollowJointTrajectoryGoal
00056 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00057 # The joint trajectory to follow
00058 trajectory_msgs/JointTrajectory trajectory
00059
00060 # Tolerances for the trajectory. If the measured joint values fall
00061 # outside the tolerances the trajectory goal is aborted. Any
00062 # tolerances that are not specified (by being omitted or set to 0) are
00063 # set to the defaults for the action server (often taken from the
00064 # parameter server).
00065
00066 # Tolerances applied to the joints as the trajectory is executed. If
00067 # violated, the goal aborts with error_code set to
00068 # PATH_TOLERANCE_VIOLATED.
00069 JointTolerance[] path_tolerance
00070
00071 # To report success, the joints must be within goal_tolerance of the
00072 # final trajectory value. The goal must be achieved by time the
00073 # trajectory ends plus goal_time_tolerance. (goal_time_tolerance
00074 # allows some leeway in time, so that the trajectory goal can still
00075 # succeed even if the joints reach the goal some time after the
00076 # precise end time of the trajectory).
00077 #
00078 # If the joints are not within goal_tolerance after "trajectory finish
00079 # time" + goal_time_tolerance, the goal aborts with error_code set to
00080 # GOAL_TOLERANCE_VIOLATED
00081 JointTolerance[] goal_tolerance
00082 duration goal_time_tolerance
00083
00084
00085 ================================================================================
00086 MSG: trajectory_msgs/JointTrajectory
00087 Header header
00088 string[] joint_names
00089 JointTrajectoryPoint[] points
00090 ================================================================================
00091 MSG: trajectory_msgs/JointTrajectoryPoint
00092 float64[] positions
00093 float64[] velocities
00094 float64[] accelerations
00095 duration time_from_start
00096 ================================================================================
00097 MSG: control_msgs/JointTolerance
00098 # The tolerances specify the amount the position, velocity, and
00099 # accelerations can vary from the setpoints. For example, in the case
00100 # of trajectory control, when the actual position varies beyond
00101 # (desired position + position tolerance), the trajectory goal may
00102 # abort.
00103 #
00104 # There are two special values for tolerances:
00105 # * 0 - The tolerance is unspecified and will remain at whatever the default is
00106 # * -1 - The tolerance is "erased". If there was a default, the joint will be
00107 # allowed to move without restriction.
00108
00109 string name
00110 float64 position # in radians or meters (for a revolute or prismatic joint, respectively)
00111 float64 velocity # in rad/sec or m/sec
00112 float64 acceleration # in rad/sec^2 or m/sec^2
00113
00114 """
00115 __slots__ = ['header','goal_id','goal']
00116 _slot_types = ['std_msgs/Header','actionlib_msgs/GoalID','control_msgs/FollowJointTrajectoryGoal']
00117
00118 def __init__(self, *args, **kwds):
00119 """
00120 Constructor. Any message fields that are implicitly/explicitly
00121 set to None will be assigned a default value. The recommend
00122 use is keyword arguments as this is more robust to future message
00123 changes. You cannot mix in-order arguments and keyword arguments.
00124
00125 The available fields are:
00126 header,goal_id,goal
00127
00128 :param args: complete set of field values, in .msg order
00129 :param kwds: use keyword arguments corresponding to message field names
00130 to set specific fields.
00131 """
00132 if args or kwds:
00133 super(FollowJointTrajectoryActionGoal, self).__init__(*args, **kwds)
00134
00135 if self.header is None:
00136 self.header = std_msgs.msg.Header()
00137 if self.goal_id is None:
00138 self.goal_id = actionlib_msgs.msg.GoalID()
00139 if self.goal is None:
00140 self.goal = control_msgs.msg.FollowJointTrajectoryGoal()
00141 else:
00142 self.header = std_msgs.msg.Header()
00143 self.goal_id = actionlib_msgs.msg.GoalID()
00144 self.goal = control_msgs.msg.FollowJointTrajectoryGoal()
00145
00146 def _get_types(self):
00147 """
00148 internal API method
00149 """
00150 return self._slot_types
00151
00152 def serialize(self, buff):
00153 """
00154 serialize message into buffer
00155 :param buff: buffer, ``StringIO``
00156 """
00157 try:
00158 _x = self
00159 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00160 _x = self.header.frame_id
00161 length = len(_x)
00162 if python3 or type(_x) == unicode:
00163 _x = _x.encode('utf-8')
00164 length = len(_x)
00165 buff.write(struct.pack('<I%ss'%length, length, _x))
00166 _x = self
00167 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00168 _x = self.goal_id.id
00169 length = len(_x)
00170 if python3 or type(_x) == unicode:
00171 _x = _x.encode('utf-8')
00172 length = len(_x)
00173 buff.write(struct.pack('<I%ss'%length, length, _x))
00174 _x = self
00175 buff.write(_struct_3I.pack(_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs))
00176 _x = self.goal.trajectory.header.frame_id
00177 length = len(_x)
00178 if python3 or type(_x) == unicode:
00179 _x = _x.encode('utf-8')
00180 length = len(_x)
00181 buff.write(struct.pack('<I%ss'%length, length, _x))
00182 length = len(self.goal.trajectory.joint_names)
00183 buff.write(_struct_I.pack(length))
00184 for val1 in self.goal.trajectory.joint_names:
00185 length = len(val1)
00186 if python3 or type(val1) == unicode:
00187 val1 = val1.encode('utf-8')
00188 length = len(val1)
00189 buff.write(struct.pack('<I%ss'%length, length, val1))
00190 length = len(self.goal.trajectory.points)
00191 buff.write(_struct_I.pack(length))
00192 for val1 in self.goal.trajectory.points:
00193 length = len(val1.positions)
00194 buff.write(_struct_I.pack(length))
00195 pattern = '<%sd'%length
00196 buff.write(struct.pack(pattern, *val1.positions))
00197 length = len(val1.velocities)
00198 buff.write(_struct_I.pack(length))
00199 pattern = '<%sd'%length
00200 buff.write(struct.pack(pattern, *val1.velocities))
00201 length = len(val1.accelerations)
00202 buff.write(_struct_I.pack(length))
00203 pattern = '<%sd'%length
00204 buff.write(struct.pack(pattern, *val1.accelerations))
00205 _v1 = val1.time_from_start
00206 _x = _v1
00207 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00208 length = len(self.goal.path_tolerance)
00209 buff.write(_struct_I.pack(length))
00210 for val1 in self.goal.path_tolerance:
00211 _x = val1.name
00212 length = len(_x)
00213 if python3 or type(_x) == unicode:
00214 _x = _x.encode('utf-8')
00215 length = len(_x)
00216 buff.write(struct.pack('<I%ss'%length, length, _x))
00217 _x = val1
00218 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00219 length = len(self.goal.goal_tolerance)
00220 buff.write(_struct_I.pack(length))
00221 for val1 in self.goal.goal_tolerance:
00222 _x = val1.name
00223 length = len(_x)
00224 if python3 or type(_x) == unicode:
00225 _x = _x.encode('utf-8')
00226 length = len(_x)
00227 buff.write(struct.pack('<I%ss'%length, length, _x))
00228 _x = val1
00229 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00230 _x = self
00231 buff.write(_struct_2i.pack(_x.goal.goal_time_tolerance.secs, _x.goal.goal_time_tolerance.nsecs))
00232 except struct.error as se: self._check_types(se)
00233 except TypeError as te: self._check_types(te)
00234
00235 def deserialize(self, str):
00236 """
00237 unpack serialized message in str into this message instance
00238 :param str: byte array of serialized message, ``str``
00239 """
00240 try:
00241 if self.header is None:
00242 self.header = std_msgs.msg.Header()
00243 if self.goal_id is None:
00244 self.goal_id = actionlib_msgs.msg.GoalID()
00245 if self.goal is None:
00246 self.goal = control_msgs.msg.FollowJointTrajectoryGoal()
00247 end = 0
00248 _x = self
00249 start = end
00250 end += 12
00251 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00252 start = end
00253 end += 4
00254 (length,) = _struct_I.unpack(str[start:end])
00255 start = end
00256 end += length
00257 if python3:
00258 self.header.frame_id = str[start:end].decode('utf-8')
00259 else:
00260 self.header.frame_id = str[start:end]
00261 _x = self
00262 start = end
00263 end += 8
00264 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00265 start = end
00266 end += 4
00267 (length,) = _struct_I.unpack(str[start:end])
00268 start = end
00269 end += length
00270 if python3:
00271 self.goal_id.id = str[start:end].decode('utf-8')
00272 else:
00273 self.goal_id.id = str[start:end]
00274 _x = self
00275 start = end
00276 end += 12
00277 (_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00278 start = end
00279 end += 4
00280 (length,) = _struct_I.unpack(str[start:end])
00281 start = end
00282 end += length
00283 if python3:
00284 self.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00285 else:
00286 self.goal.trajectory.header.frame_id = str[start:end]
00287 start = end
00288 end += 4
00289 (length,) = _struct_I.unpack(str[start:end])
00290 self.goal.trajectory.joint_names = []
00291 for i in range(0, length):
00292 start = end
00293 end += 4
00294 (length,) = _struct_I.unpack(str[start:end])
00295 start = end
00296 end += length
00297 if python3:
00298 val1 = str[start:end].decode('utf-8')
00299 else:
00300 val1 = str[start:end]
00301 self.goal.trajectory.joint_names.append(val1)
00302 start = end
00303 end += 4
00304 (length,) = _struct_I.unpack(str[start:end])
00305 self.goal.trajectory.points = []
00306 for i in range(0, length):
00307 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00308 start = end
00309 end += 4
00310 (length,) = _struct_I.unpack(str[start:end])
00311 pattern = '<%sd'%length
00312 start = end
00313 end += struct.calcsize(pattern)
00314 val1.positions = struct.unpack(pattern, str[start:end])
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 pattern = '<%sd'%length
00319 start = end
00320 end += struct.calcsize(pattern)
00321 val1.velocities = struct.unpack(pattern, str[start:end])
00322 start = end
00323 end += 4
00324 (length,) = _struct_I.unpack(str[start:end])
00325 pattern = '<%sd'%length
00326 start = end
00327 end += struct.calcsize(pattern)
00328 val1.accelerations = struct.unpack(pattern, str[start:end])
00329 _v2 = val1.time_from_start
00330 _x = _v2
00331 start = end
00332 end += 8
00333 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00334 self.goal.trajectory.points.append(val1)
00335 start = end
00336 end += 4
00337 (length,) = _struct_I.unpack(str[start:end])
00338 self.goal.path_tolerance = []
00339 for i in range(0, length):
00340 val1 = control_msgs.msg.JointTolerance()
00341 start = end
00342 end += 4
00343 (length,) = _struct_I.unpack(str[start:end])
00344 start = end
00345 end += length
00346 if python3:
00347 val1.name = str[start:end].decode('utf-8')
00348 else:
00349 val1.name = str[start:end]
00350 _x = val1
00351 start = end
00352 end += 24
00353 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
00354 self.goal.path_tolerance.append(val1)
00355 start = end
00356 end += 4
00357 (length,) = _struct_I.unpack(str[start:end])
00358 self.goal.goal_tolerance = []
00359 for i in range(0, length):
00360 val1 = control_msgs.msg.JointTolerance()
00361 start = end
00362 end += 4
00363 (length,) = _struct_I.unpack(str[start:end])
00364 start = end
00365 end += length
00366 if python3:
00367 val1.name = str[start:end].decode('utf-8')
00368 else:
00369 val1.name = str[start:end]
00370 _x = val1
00371 start = end
00372 end += 24
00373 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
00374 self.goal.goal_tolerance.append(val1)
00375 _x = self
00376 start = end
00377 end += 8
00378 (_x.goal.goal_time_tolerance.secs, _x.goal.goal_time_tolerance.nsecs,) = _struct_2i.unpack(str[start:end])
00379 return self
00380 except struct.error as e:
00381 raise genpy.DeserializationError(e)
00382
00383
00384 def serialize_numpy(self, buff, numpy):
00385 """
00386 serialize message with numpy array types into buffer
00387 :param buff: buffer, ``StringIO``
00388 :param numpy: numpy python module
00389 """
00390 try:
00391 _x = self
00392 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00393 _x = self.header.frame_id
00394 length = len(_x)
00395 if python3 or type(_x) == unicode:
00396 _x = _x.encode('utf-8')
00397 length = len(_x)
00398 buff.write(struct.pack('<I%ss'%length, length, _x))
00399 _x = self
00400 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00401 _x = self.goal_id.id
00402 length = len(_x)
00403 if python3 or type(_x) == unicode:
00404 _x = _x.encode('utf-8')
00405 length = len(_x)
00406 buff.write(struct.pack('<I%ss'%length, length, _x))
00407 _x = self
00408 buff.write(_struct_3I.pack(_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs))
00409 _x = self.goal.trajectory.header.frame_id
00410 length = len(_x)
00411 if python3 or type(_x) == unicode:
00412 _x = _x.encode('utf-8')
00413 length = len(_x)
00414 buff.write(struct.pack('<I%ss'%length, length, _x))
00415 length = len(self.goal.trajectory.joint_names)
00416 buff.write(_struct_I.pack(length))
00417 for val1 in self.goal.trajectory.joint_names:
00418 length = len(val1)
00419 if python3 or type(val1) == unicode:
00420 val1 = val1.encode('utf-8')
00421 length = len(val1)
00422 buff.write(struct.pack('<I%ss'%length, length, val1))
00423 length = len(self.goal.trajectory.points)
00424 buff.write(_struct_I.pack(length))
00425 for val1 in self.goal.trajectory.points:
00426 length = len(val1.positions)
00427 buff.write(_struct_I.pack(length))
00428 pattern = '<%sd'%length
00429 buff.write(val1.positions.tostring())
00430 length = len(val1.velocities)
00431 buff.write(_struct_I.pack(length))
00432 pattern = '<%sd'%length
00433 buff.write(val1.velocities.tostring())
00434 length = len(val1.accelerations)
00435 buff.write(_struct_I.pack(length))
00436 pattern = '<%sd'%length
00437 buff.write(val1.accelerations.tostring())
00438 _v3 = val1.time_from_start
00439 _x = _v3
00440 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00441 length = len(self.goal.path_tolerance)
00442 buff.write(_struct_I.pack(length))
00443 for val1 in self.goal.path_tolerance:
00444 _x = val1.name
00445 length = len(_x)
00446 if python3 or type(_x) == unicode:
00447 _x = _x.encode('utf-8')
00448 length = len(_x)
00449 buff.write(struct.pack('<I%ss'%length, length, _x))
00450 _x = val1
00451 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00452 length = len(self.goal.goal_tolerance)
00453 buff.write(_struct_I.pack(length))
00454 for val1 in self.goal.goal_tolerance:
00455 _x = val1.name
00456 length = len(_x)
00457 if python3 or type(_x) == unicode:
00458 _x = _x.encode('utf-8')
00459 length = len(_x)
00460 buff.write(struct.pack('<I%ss'%length, length, _x))
00461 _x = val1
00462 buff.write(_struct_3d.pack(_x.position, _x.velocity, _x.acceleration))
00463 _x = self
00464 buff.write(_struct_2i.pack(_x.goal.goal_time_tolerance.secs, _x.goal.goal_time_tolerance.nsecs))
00465 except struct.error as se: self._check_types(se)
00466 except TypeError as te: self._check_types(te)
00467
00468 def deserialize_numpy(self, str, numpy):
00469 """
00470 unpack serialized message in str into this message instance using numpy for array types
00471 :param str: byte array of serialized message, ``str``
00472 :param numpy: numpy python module
00473 """
00474 try:
00475 if self.header is None:
00476 self.header = std_msgs.msg.Header()
00477 if self.goal_id is None:
00478 self.goal_id = actionlib_msgs.msg.GoalID()
00479 if self.goal is None:
00480 self.goal = control_msgs.msg.FollowJointTrajectoryGoal()
00481 end = 0
00482 _x = self
00483 start = end
00484 end += 12
00485 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00486 start = end
00487 end += 4
00488 (length,) = _struct_I.unpack(str[start:end])
00489 start = end
00490 end += length
00491 if python3:
00492 self.header.frame_id = str[start:end].decode('utf-8')
00493 else:
00494 self.header.frame_id = str[start:end]
00495 _x = self
00496 start = end
00497 end += 8
00498 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00499 start = end
00500 end += 4
00501 (length,) = _struct_I.unpack(str[start:end])
00502 start = end
00503 end += length
00504 if python3:
00505 self.goal_id.id = str[start:end].decode('utf-8')
00506 else:
00507 self.goal_id.id = str[start:end]
00508 _x = self
00509 start = end
00510 end += 12
00511 (_x.goal.trajectory.header.seq, _x.goal.trajectory.header.stamp.secs, _x.goal.trajectory.header.stamp.nsecs,) = _struct_3I.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 if python3:
00518 self.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00519 else:
00520 self.goal.trajectory.header.frame_id = str[start:end]
00521 start = end
00522 end += 4
00523 (length,) = _struct_I.unpack(str[start:end])
00524 self.goal.trajectory.joint_names = []
00525 for i in range(0, length):
00526 start = end
00527 end += 4
00528 (length,) = _struct_I.unpack(str[start:end])
00529 start = end
00530 end += length
00531 if python3:
00532 val1 = str[start:end].decode('utf-8')
00533 else:
00534 val1 = str[start:end]
00535 self.goal.trajectory.joint_names.append(val1)
00536 start = end
00537 end += 4
00538 (length,) = _struct_I.unpack(str[start:end])
00539 self.goal.trajectory.points = []
00540 for i in range(0, length):
00541 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00542 start = end
00543 end += 4
00544 (length,) = _struct_I.unpack(str[start:end])
00545 pattern = '<%sd'%length
00546 start = end
00547 end += struct.calcsize(pattern)
00548 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00549 start = end
00550 end += 4
00551 (length,) = _struct_I.unpack(str[start:end])
00552 pattern = '<%sd'%length
00553 start = end
00554 end += struct.calcsize(pattern)
00555 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00556 start = end
00557 end += 4
00558 (length,) = _struct_I.unpack(str[start:end])
00559 pattern = '<%sd'%length
00560 start = end
00561 end += struct.calcsize(pattern)
00562 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00563 _v4 = val1.time_from_start
00564 _x = _v4
00565 start = end
00566 end += 8
00567 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00568 self.goal.trajectory.points.append(val1)
00569 start = end
00570 end += 4
00571 (length,) = _struct_I.unpack(str[start:end])
00572 self.goal.path_tolerance = []
00573 for i in range(0, length):
00574 val1 = control_msgs.msg.JointTolerance()
00575 start = end
00576 end += 4
00577 (length,) = _struct_I.unpack(str[start:end])
00578 start = end
00579 end += length
00580 if python3:
00581 val1.name = str[start:end].decode('utf-8')
00582 else:
00583 val1.name = str[start:end]
00584 _x = val1
00585 start = end
00586 end += 24
00587 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
00588 self.goal.path_tolerance.append(val1)
00589 start = end
00590 end += 4
00591 (length,) = _struct_I.unpack(str[start:end])
00592 self.goal.goal_tolerance = []
00593 for i in range(0, length):
00594 val1 = control_msgs.msg.JointTolerance()
00595 start = end
00596 end += 4
00597 (length,) = _struct_I.unpack(str[start:end])
00598 start = end
00599 end += length
00600 if python3:
00601 val1.name = str[start:end].decode('utf-8')
00602 else:
00603 val1.name = str[start:end]
00604 _x = val1
00605 start = end
00606 end += 24
00607 (_x.position, _x.velocity, _x.acceleration,) = _struct_3d.unpack(str[start:end])
00608 self.goal.goal_tolerance.append(val1)
00609 _x = self
00610 start = end
00611 end += 8
00612 (_x.goal.goal_time_tolerance.secs, _x.goal.goal_time_tolerance.nsecs,) = _struct_2i.unpack(str[start:end])
00613 return self
00614 except struct.error as e:
00615 raise genpy.DeserializationError(e)
00616
00617 _struct_I = genpy.struct_I
00618 _struct_3I = struct.Struct("<3I")
00619 _struct_3d = struct.Struct("<3d")
00620 _struct_2I = struct.Struct("<2I")
00621 _struct_2i = struct.Struct("<2i")