00001 """autogenerated by genpy from pr2_gripper_sensor_msgs/PR2GripperReleaseAction.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 genpy
00008 import actionlib_msgs.msg
00009 import pr2_gripper_sensor_msgs.msg
00010 import std_msgs.msg
00011
00012 class PR2GripperReleaseAction(genpy.Message):
00013 _md5sum = "c3c9b6394f2bb7d0d9e5ed002d9a759a"
00014 _type = "pr2_gripper_sensor_msgs/PR2GripperReleaseAction"
00015 _has_header = False
00016 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00017
00018 PR2GripperReleaseActionGoal action_goal
00019 PR2GripperReleaseActionResult action_result
00020 PR2GripperReleaseActionFeedback action_feedback
00021
00022 ================================================================================
00023 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseActionGoal
00024 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00025
00026 Header header
00027 actionlib_msgs/GoalID goal_id
00028 PR2GripperReleaseGoal goal
00029
00030 ================================================================================
00031 MSG: std_msgs/Header
00032 # Standard metadata for higher-level stamped data types.
00033 # This is generally used to communicate timestamped data
00034 # in a particular coordinate frame.
00035 #
00036 # sequence ID: consecutively increasing ID
00037 uint32 seq
00038 #Two-integer timestamp that is expressed as:
00039 # * stamp.secs: seconds (stamp_secs) since epoch
00040 # * stamp.nsecs: nanoseconds since stamp_secs
00041 # time-handling sugar is provided by the client library
00042 time stamp
00043 #Frame this data is associated with
00044 # 0: no frame
00045 # 1: global frame
00046 string frame_id
00047
00048 ================================================================================
00049 MSG: actionlib_msgs/GoalID
00050 # The stamp should store the time at which this goal was requested.
00051 # It is used by an action server when it tries to preempt all
00052 # goals that were requested before a certain time
00053 time stamp
00054
00055 # The id provides a way to associate feedback and
00056 # result message with specific goal requests. The id
00057 # specified must be unique.
00058 string id
00059
00060
00061 ================================================================================
00062 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseGoal
00063 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00064 #goal
00065 PR2GripperReleaseCommand command
00066
00067 ================================================================================
00068 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseCommand
00069 # the event conditions we would like to trigger the robot to release on
00070 PR2GripperEventDetectorCommand event
00071 ================================================================================
00072 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand
00073 # state variable that defines what events we would like to trigger on
00074 # Leaving this field blank will result in the robot triggering when
00075 # anything touches the sides of the finger or an impact is detected
00076 # with the hand/arm.
00077 int8 trigger_conditions
00078 # definitions for our various trigger_conditions values
00079 # trigger on either acceleration contact or finger sensor side impact
00080 int8 FINGER_SIDE_IMPACT_OR_ACC = 0
00081 # tigger once both slip and acceleration signals occur
00082 int8 SLIP_AND_ACC = 1
00083 # trigger on either slip, acceleration, or finger sensor side impact
00084 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2
00085 # trigger only on slip information
00086 int8 SLIP = 3
00087 # trigger only on acceleration contact information
00088 int8 ACC = 4
00089
00090
00091 # the amount of acceleration to trigger on (acceleration vector magnitude)
00092 # Units = m/s^2
00093 # The user needs to be concerned here about not setting the trigger too
00094 # low so that is set off by the robot's own motions.
00095 #
00096 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level
00097 # For small delicate controlled motions this can be set MUCH lower (try 2.0)
00098 #
00099 # NOTE: When moving the gripper joint (opening/closing the grippr)
00100 # the high gearing of the PR2 gripper causes large acceleration vibrations
00101 # which will cause triggering to occur. This is a known drawback of the PR2.
00102 #
00103 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you
00104 # are using a trigger_conditions value that returns on acceleration contact
00105 # events then it will immediately exceed your trigger and return
00106 float64 acceleration_trigger_magnitude
00107
00108
00109 # the slip detector gain to trigger on (either finger) : try 0.01
00110 # higher values decrease slip sensitivty (to a point)
00111 # lower values increase sensitivity (to a point)
00112 #
00113 # NOTE: Leaving this value blank will result in the most sensitive slip level.
00114 float64 slip_trigger_magnitude
00115 ================================================================================
00116 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseActionResult
00117 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00118
00119 Header header
00120 actionlib_msgs/GoalStatus status
00121 PR2GripperReleaseResult result
00122
00123 ================================================================================
00124 MSG: actionlib_msgs/GoalStatus
00125 GoalID goal_id
00126 uint8 status
00127 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00128 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00129 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00130 # and has since completed its execution (Terminal State)
00131 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00132 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00133 # to some failure (Terminal State)
00134 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00135 # because the goal was unattainable or invalid (Terminal State)
00136 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00137 # and has not yet completed execution
00138 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00139 # but the action server has not yet confirmed that the goal is canceled
00140 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00141 # and was successfully cancelled (Terminal State)
00142 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00143 # sent over the wire by an action server
00144
00145 #Allow for the user to associate a string with GoalStatus for debugging
00146 string text
00147
00148
00149 ================================================================================
00150 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseResult
00151 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00152 #result
00153 PR2GripperReleaseData data
00154
00155 ================================================================================
00156 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseData
00157 # the control state of our realtime controller
00158 PR2GripperSensorRTState rtstate
00159 ================================================================================
00160 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState
00161 # the control state of our realtime controller
00162 int8 realtime_controller_state
00163
00164 # predefined values to indicate our realtime_controller_state
00165 int8 DISABLED = 0
00166 int8 POSITION_SERVO = 3
00167 int8 FORCE_SERVO = 4
00168 int8 FIND_CONTACT = 5
00169 int8 SLIP_SERVO = 6
00170 ================================================================================
00171 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseActionFeedback
00172 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00173
00174 Header header
00175 actionlib_msgs/GoalStatus status
00176 PR2GripperReleaseFeedback feedback
00177
00178 ================================================================================
00179 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseFeedback
00180 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00181
00182 #feedback
00183 PR2GripperReleaseData data
00184
00185
00186 """
00187 __slots__ = ['action_goal','action_result','action_feedback']
00188 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperReleaseActionGoal','pr2_gripper_sensor_msgs/PR2GripperReleaseActionResult','pr2_gripper_sensor_msgs/PR2GripperReleaseActionFeedback']
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(PR2GripperReleaseAction, self).__init__(*args, **kwds)
00206
00207 if self.action_goal is None:
00208 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00209 if self.action_result is None:
00210 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00211 if self.action_feedback is None:
00212 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00213 else:
00214 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00215 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00216 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
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_b2d3I.pack(_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00248 _x = self.action_result.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 _x = self
00255 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00256 _x = self.action_result.status.goal_id.id
00257 length = len(_x)
00258 if python3 or type(_x) == unicode:
00259 _x = _x.encode('utf-8')
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 buff.write(_struct_B.pack(self.action_result.status.status))
00263 _x = self.action_result.status.text
00264 length = len(_x)
00265 if python3 or type(_x) == unicode:
00266 _x = _x.encode('utf-8')
00267 length = len(_x)
00268 buff.write(struct.pack('<I%ss'%length, length, _x))
00269 _x = self
00270 buff.write(_struct_b3I.pack(_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00271 _x = self.action_feedback.header.frame_id
00272 length = len(_x)
00273 if python3 or type(_x) == unicode:
00274 _x = _x.encode('utf-8')
00275 length = len(_x)
00276 buff.write(struct.pack('<I%ss'%length, length, _x))
00277 _x = self
00278 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00279 _x = self.action_feedback.status.goal_id.id
00280 length = len(_x)
00281 if python3 or type(_x) == unicode:
00282 _x = _x.encode('utf-8')
00283 length = len(_x)
00284 buff.write(struct.pack('<I%ss'%length, length, _x))
00285 buff.write(_struct_B.pack(self.action_feedback.status.status))
00286 _x = self.action_feedback.status.text
00287 length = len(_x)
00288 if python3 or type(_x) == unicode:
00289 _x = _x.encode('utf-8')
00290 length = len(_x)
00291 buff.write(struct.pack('<I%ss'%length, length, _x))
00292 buff.write(_struct_b.pack(self.action_feedback.feedback.data.rtstate.realtime_controller_state))
00293 except struct.error as se: self._check_types(se)
00294 except TypeError as te: self._check_types(te)
00295
00296 def deserialize(self, str):
00297 """
00298 unpack serialized message in str into this message instance
00299 :param str: byte array of serialized message, ``str``
00300 """
00301 try:
00302 if self.action_goal is None:
00303 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00304 if self.action_result is None:
00305 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00306 if self.action_feedback is None:
00307 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00308 end = 0
00309 _x = self
00310 start = end
00311 end += 12
00312 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00313 start = end
00314 end += 4
00315 (length,) = _struct_I.unpack(str[start:end])
00316 start = end
00317 end += length
00318 if python3:
00319 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00320 else:
00321 self.action_goal.header.frame_id = str[start:end]
00322 _x = self
00323 start = end
00324 end += 8
00325 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00326 start = end
00327 end += 4
00328 (length,) = _struct_I.unpack(str[start:end])
00329 start = end
00330 end += length
00331 if python3:
00332 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00333 else:
00334 self.action_goal.goal_id.id = str[start:end]
00335 _x = self
00336 start = end
00337 end += 29
00338 (_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_b2d3I.unpack(str[start:end])
00339 start = end
00340 end += 4
00341 (length,) = _struct_I.unpack(str[start:end])
00342 start = end
00343 end += length
00344 if python3:
00345 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00346 else:
00347 self.action_result.header.frame_id = str[start:end]
00348 _x = self
00349 start = end
00350 end += 8
00351 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00352 start = end
00353 end += 4
00354 (length,) = _struct_I.unpack(str[start:end])
00355 start = end
00356 end += length
00357 if python3:
00358 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00359 else:
00360 self.action_result.status.goal_id.id = str[start:end]
00361 start = end
00362 end += 1
00363 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00364 start = end
00365 end += 4
00366 (length,) = _struct_I.unpack(str[start:end])
00367 start = end
00368 end += length
00369 if python3:
00370 self.action_result.status.text = str[start:end].decode('utf-8')
00371 else:
00372 self.action_result.status.text = str[start:end]
00373 _x = self
00374 start = end
00375 end += 13
00376 (_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end])
00377 start = end
00378 end += 4
00379 (length,) = _struct_I.unpack(str[start:end])
00380 start = end
00381 end += length
00382 if python3:
00383 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00384 else:
00385 self.action_feedback.header.frame_id = str[start:end]
00386 _x = self
00387 start = end
00388 end += 8
00389 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00390 start = end
00391 end += 4
00392 (length,) = _struct_I.unpack(str[start:end])
00393 start = end
00394 end += length
00395 if python3:
00396 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00397 else:
00398 self.action_feedback.status.goal_id.id = str[start:end]
00399 start = end
00400 end += 1
00401 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00402 start = end
00403 end += 4
00404 (length,) = _struct_I.unpack(str[start:end])
00405 start = end
00406 end += length
00407 if python3:
00408 self.action_feedback.status.text = str[start:end].decode('utf-8')
00409 else:
00410 self.action_feedback.status.text = str[start:end]
00411 start = end
00412 end += 1
00413 (self.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_b.unpack(str[start:end])
00414 return self
00415 except struct.error as e:
00416 raise genpy.DeserializationError(e)
00417
00418
00419 def serialize_numpy(self, buff, numpy):
00420 """
00421 serialize message with numpy array types into buffer
00422 :param buff: buffer, ``StringIO``
00423 :param numpy: numpy python module
00424 """
00425 try:
00426 _x = self
00427 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00428 _x = self.action_goal.header.frame_id
00429 length = len(_x)
00430 if python3 or type(_x) == unicode:
00431 _x = _x.encode('utf-8')
00432 length = len(_x)
00433 buff.write(struct.pack('<I%ss'%length, length, _x))
00434 _x = self
00435 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00436 _x = self.action_goal.goal_id.id
00437 length = len(_x)
00438 if python3 or type(_x) == unicode:
00439 _x = _x.encode('utf-8')
00440 length = len(_x)
00441 buff.write(struct.pack('<I%ss'%length, length, _x))
00442 _x = self
00443 buff.write(_struct_b2d3I.pack(_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00444 _x = self.action_result.header.frame_id
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 = self
00451 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00452 _x = self.action_result.status.goal_id.id
00453 length = len(_x)
00454 if python3 or type(_x) == unicode:
00455 _x = _x.encode('utf-8')
00456 length = len(_x)
00457 buff.write(struct.pack('<I%ss'%length, length, _x))
00458 buff.write(_struct_B.pack(self.action_result.status.status))
00459 _x = self.action_result.status.text
00460 length = len(_x)
00461 if python3 or type(_x) == unicode:
00462 _x = _x.encode('utf-8')
00463 length = len(_x)
00464 buff.write(struct.pack('<I%ss'%length, length, _x))
00465 _x = self
00466 buff.write(_struct_b3I.pack(_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00467 _x = self.action_feedback.header.frame_id
00468 length = len(_x)
00469 if python3 or type(_x) == unicode:
00470 _x = _x.encode('utf-8')
00471 length = len(_x)
00472 buff.write(struct.pack('<I%ss'%length, length, _x))
00473 _x = self
00474 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00475 _x = self.action_feedback.status.goal_id.id
00476 length = len(_x)
00477 if python3 or type(_x) == unicode:
00478 _x = _x.encode('utf-8')
00479 length = len(_x)
00480 buff.write(struct.pack('<I%ss'%length, length, _x))
00481 buff.write(_struct_B.pack(self.action_feedback.status.status))
00482 _x = self.action_feedback.status.text
00483 length = len(_x)
00484 if python3 or type(_x) == unicode:
00485 _x = _x.encode('utf-8')
00486 length = len(_x)
00487 buff.write(struct.pack('<I%ss'%length, length, _x))
00488 buff.write(_struct_b.pack(self.action_feedback.feedback.data.rtstate.realtime_controller_state))
00489 except struct.error as se: self._check_types(se)
00490 except TypeError as te: self._check_types(te)
00491
00492 def deserialize_numpy(self, str, numpy):
00493 """
00494 unpack serialized message in str into this message instance using numpy for array types
00495 :param str: byte array of serialized message, ``str``
00496 :param numpy: numpy python module
00497 """
00498 try:
00499 if self.action_goal is None:
00500 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00501 if self.action_result is None:
00502 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00503 if self.action_feedback is None:
00504 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00505 end = 0
00506 _x = self
00507 start = end
00508 end += 12
00509 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00510 start = end
00511 end += 4
00512 (length,) = _struct_I.unpack(str[start:end])
00513 start = end
00514 end += length
00515 if python3:
00516 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00517 else:
00518 self.action_goal.header.frame_id = str[start:end]
00519 _x = self
00520 start = end
00521 end += 8
00522 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00523 start = end
00524 end += 4
00525 (length,) = _struct_I.unpack(str[start:end])
00526 start = end
00527 end += length
00528 if python3:
00529 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00530 else:
00531 self.action_goal.goal_id.id = str[start:end]
00532 _x = self
00533 start = end
00534 end += 29
00535 (_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_b2d3I.unpack(str[start:end])
00536 start = end
00537 end += 4
00538 (length,) = _struct_I.unpack(str[start:end])
00539 start = end
00540 end += length
00541 if python3:
00542 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00543 else:
00544 self.action_result.header.frame_id = str[start:end]
00545 _x = self
00546 start = end
00547 end += 8
00548 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00549 start = end
00550 end += 4
00551 (length,) = _struct_I.unpack(str[start:end])
00552 start = end
00553 end += length
00554 if python3:
00555 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00556 else:
00557 self.action_result.status.goal_id.id = str[start:end]
00558 start = end
00559 end += 1
00560 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00561 start = end
00562 end += 4
00563 (length,) = _struct_I.unpack(str[start:end])
00564 start = end
00565 end += length
00566 if python3:
00567 self.action_result.status.text = str[start:end].decode('utf-8')
00568 else:
00569 self.action_result.status.text = str[start:end]
00570 _x = self
00571 start = end
00572 end += 13
00573 (_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end])
00574 start = end
00575 end += 4
00576 (length,) = _struct_I.unpack(str[start:end])
00577 start = end
00578 end += length
00579 if python3:
00580 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00581 else:
00582 self.action_feedback.header.frame_id = str[start:end]
00583 _x = self
00584 start = end
00585 end += 8
00586 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00587 start = end
00588 end += 4
00589 (length,) = _struct_I.unpack(str[start:end])
00590 start = end
00591 end += length
00592 if python3:
00593 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00594 else:
00595 self.action_feedback.status.goal_id.id = str[start:end]
00596 start = end
00597 end += 1
00598 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00599 start = end
00600 end += 4
00601 (length,) = _struct_I.unpack(str[start:end])
00602 start = end
00603 end += length
00604 if python3:
00605 self.action_feedback.status.text = str[start:end].decode('utf-8')
00606 else:
00607 self.action_feedback.status.text = str[start:end]
00608 start = end
00609 end += 1
00610 (self.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_b.unpack(str[start:end])
00611 return self
00612 except struct.error as e:
00613 raise genpy.DeserializationError(e)
00614
00615 _struct_I = genpy.struct_I
00616 _struct_B = struct.Struct("<B")
00617 _struct_b2d3I = struct.Struct("<b2d3I")
00618 _struct_3I = struct.Struct("<3I")
00619 _struct_b = struct.Struct("<b")
00620 _struct_b3I = struct.Struct("<b3I")
00621 _struct_2I = struct.Struct("<2I")