00001 """autogenerated by genmsg_py from PR2GripperSlipServoAction.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import actionlib_msgs.msg
00007 import pr2_gripper_sensor_msgs.msg
00008 import std_msgs.msg
00009
00010 class PR2GripperSlipServoAction(roslib.message.Message):
00011 _md5sum = "d1abef6e5d417a62bf67570de0fcd426"
00012 _type = "pr2_gripper_sensor_msgs/PR2GripperSlipServoAction"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015
00016 PR2GripperSlipServoActionGoal action_goal
00017 PR2GripperSlipServoActionResult action_result
00018 PR2GripperSlipServoActionFeedback action_feedback
00019
00020 ================================================================================
00021 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoActionGoal
00022 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00023
00024 Header header
00025 actionlib_msgs/GoalID goal_id
00026 PR2GripperSlipServoGoal goal
00027
00028 ================================================================================
00029 MSG: std_msgs/Header
00030 # Standard metadata for higher-level stamped data types.
00031 # This is generally used to communicate timestamped data
00032 # in a particular coordinate frame.
00033 #
00034 # sequence ID: consecutively increasing ID
00035 uint32 seq
00036 #Two-integer timestamp that is expressed as:
00037 # * stamp.secs: seconds (stamp_secs) since epoch
00038 # * stamp.nsecs: nanoseconds since stamp_secs
00039 # time-handling sugar is provided by the client library
00040 time stamp
00041 #Frame this data is associated with
00042 # 0: no frame
00043 # 1: global frame
00044 string frame_id
00045
00046 ================================================================================
00047 MSG: actionlib_msgs/GoalID
00048 # The stamp should store the time at which this goal was requested.
00049 # It is used by an action server when it tries to preempt all
00050 # goals that were requested before a certain time
00051 time stamp
00052
00053 # The id provides a way to associate feedback and
00054 # result message with specific goal requests. The id
00055 # specified must be unique.
00056 string id
00057
00058
00059 ================================================================================
00060 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoGoal
00061 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00062 # Action to launch the gripper into slip servoing mode
00063
00064 #goals
00065 PR2GripperSlipServoCommand command
00066
00067 ================================================================================
00068 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoCommand
00069 # this command is currently blank, but may see additional variable
00070 # additions in the future
00071
00072 # see the param server documentation for a list of variables that effect
00073 # slip servo performance
00074 ================================================================================
00075 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoActionResult
00076 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00077
00078 Header header
00079 actionlib_msgs/GoalStatus status
00080 PR2GripperSlipServoResult result
00081
00082 ================================================================================
00083 MSG: actionlib_msgs/GoalStatus
00084 GoalID goal_id
00085 uint8 status
00086 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00087 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00088 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00089 # and has since completed its execution (Terminal State)
00090 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00091 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00092 # to some failure (Terminal State)
00093 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00094 # because the goal was unattainable or invalid (Terminal State)
00095 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00096 # and has not yet completed execution
00097 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00098 # but the action server has not yet confirmed that the goal is canceled
00099 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00100 # and was successfully cancelled (Terminal State)
00101 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00102 # sent over the wire by an action server
00103
00104 #Allow for the user to associate a string with GoalStatus for debugging
00105 string text
00106
00107
00108 ================================================================================
00109 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoResult
00110 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00111
00112 #result
00113 PR2GripperSlipServoData data
00114
00115
00116 ================================================================================
00117 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoData
00118 # time the data was recorded at
00119 time stamp
00120
00121 # the amount of deformation from action start (in meters)
00122 float64 deformation
00123
00124 # the force experinced by the finger Pads (N)
00125 # NOTE:this ignores data from the edges of the finger pressure
00126 float64 left_fingertip_pad_force
00127 float64 right_fingertip_pad_force
00128
00129 # the current virtual parallel joint effort of the gripper (in N)
00130 float64 joint_effort
00131
00132 # true if the object recently slipped
00133 bool slip_detected
00134
00135 # true if we are at or exceeding the deformation limit
00136 # (see wiki page and param server for more info)
00137 bool deformation_limit_reached
00138
00139 # true if we are at or exceeding our force
00140 # (see wiki page and param server for more info)
00141 bool fingertip_force_limit_reached
00142
00143 # true if the controller thinks the gripper is empty
00144 # (see wiki page for more info)
00145 bool gripper_empty
00146
00147 # the control state of our realtime controller
00148 PR2GripperSensorRTState rtstate
00149 ================================================================================
00150 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState
00151 # the control state of our realtime controller
00152 int8 realtime_controller_state
00153
00154 # predefined values to indicate our realtime_controller_state
00155 int8 DISABLED = 0
00156 int8 POSITION_SERVO = 3
00157 int8 FORCE_SERVO = 4
00158 int8 FIND_CONTACT = 5
00159 int8 SLIP_SERVO = 6
00160 ================================================================================
00161 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoActionFeedback
00162 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00163
00164 Header header
00165 actionlib_msgs/GoalStatus status
00166 PR2GripperSlipServoFeedback feedback
00167
00168 ================================================================================
00169 MSG: pr2_gripper_sensor_msgs/PR2GripperSlipServoFeedback
00170 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00171
00172 #feedback
00173 PR2GripperSlipServoData data
00174
00175 """
00176 __slots__ = ['action_goal','action_result','action_feedback']
00177 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperSlipServoActionGoal','pr2_gripper_sensor_msgs/PR2GripperSlipServoActionResult','pr2_gripper_sensor_msgs/PR2GripperSlipServoActionFeedback']
00178
00179 def __init__(self, *args, **kwds):
00180 """
00181 Constructor. Any message fields that are implicitly/explicitly
00182 set to None will be assigned a default value. The recommend
00183 use is keyword arguments as this is more robust to future message
00184 changes. You cannot mix in-order arguments and keyword arguments.
00185
00186 The available fields are:
00187 action_goal,action_result,action_feedback
00188
00189 @param args: complete set of field values, in .msg order
00190 @param kwds: use keyword arguments corresponding to message field names
00191 to set specific fields.
00192 """
00193 if args or kwds:
00194 super(PR2GripperSlipServoAction, self).__init__(*args, **kwds)
00195
00196 if self.action_goal is None:
00197 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionGoal()
00198 if self.action_result is None:
00199 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionResult()
00200 if self.action_feedback is None:
00201 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionFeedback()
00202 else:
00203 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionGoal()
00204 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionResult()
00205 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionFeedback()
00206
00207 def _get_types(self):
00208 """
00209 internal API method
00210 """
00211 return self._slot_types
00212
00213 def serialize(self, buff):
00214 """
00215 serialize message into buffer
00216 @param buff: buffer
00217 @type buff: StringIO
00218 """
00219 try:
00220 _x = self
00221 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00222 _x = self.action_goal.header.frame_id
00223 length = len(_x)
00224 buff.write(struct.pack('<I%ss'%length, length, _x))
00225 _x = self
00226 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00227 _x = self.action_goal.goal_id.id
00228 length = len(_x)
00229 buff.write(struct.pack('<I%ss'%length, length, _x))
00230 _x = self
00231 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00232 _x = self.action_result.header.frame_id
00233 length = len(_x)
00234 buff.write(struct.pack('<I%ss'%length, length, _x))
00235 _x = self
00236 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00237 _x = self.action_result.status.goal_id.id
00238 length = len(_x)
00239 buff.write(struct.pack('<I%ss'%length, length, _x))
00240 buff.write(_struct_B.pack(self.action_result.status.status))
00241 _x = self.action_result.status.text
00242 length = len(_x)
00243 buff.write(struct.pack('<I%ss'%length, length, _x))
00244 _x = self
00245 buff.write(_struct_2I4d4Bb3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.deformation, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.slip_detected, _x.action_result.result.data.deformation_limit_reached, _x.action_result.result.data.fingertip_force_limit_reached, _x.action_result.result.data.gripper_empty, _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))
00246 _x = self.action_feedback.header.frame_id
00247 length = len(_x)
00248 buff.write(struct.pack('<I%ss'%length, length, _x))
00249 _x = self
00250 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00251 _x = self.action_feedback.status.goal_id.id
00252 length = len(_x)
00253 buff.write(struct.pack('<I%ss'%length, length, _x))
00254 buff.write(_struct_B.pack(self.action_feedback.status.status))
00255 _x = self.action_feedback.status.text
00256 length = len(_x)
00257 buff.write(struct.pack('<I%ss'%length, length, _x))
00258 _x = self
00259 buff.write(_struct_2I4d4Bb.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.deformation, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.slip_detected, _x.action_feedback.feedback.data.deformation_limit_reached, _x.action_feedback.feedback.data.fingertip_force_limit_reached, _x.action_feedback.feedback.data.gripper_empty, _x.action_feedback.feedback.data.rtstate.realtime_controller_state))
00260 except struct.error, se: self._check_types(se)
00261 except TypeError, te: self._check_types(te)
00262
00263 def deserialize(self, str):
00264 """
00265 unpack serialized message in str into this message instance
00266 @param str: byte array of serialized message
00267 @type str: str
00268 """
00269 try:
00270 if self.action_goal is None:
00271 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionGoal()
00272 if self.action_result is None:
00273 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionResult()
00274 if self.action_feedback is None:
00275 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionFeedback()
00276 end = 0
00277 _x = self
00278 start = end
00279 end += 12
00280 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00281 start = end
00282 end += 4
00283 (length,) = _struct_I.unpack(str[start:end])
00284 start = end
00285 end += length
00286 self.action_goal.header.frame_id = str[start:end]
00287 _x = self
00288 start = end
00289 end += 8
00290 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00291 start = end
00292 end += 4
00293 (length,) = _struct_I.unpack(str[start:end])
00294 start = end
00295 end += length
00296 self.action_goal.goal_id.id = str[start:end]
00297 _x = self
00298 start = end
00299 end += 12
00300 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00301 start = end
00302 end += 4
00303 (length,) = _struct_I.unpack(str[start:end])
00304 start = end
00305 end += length
00306 self.action_result.header.frame_id = str[start:end]
00307 _x = self
00308 start = end
00309 end += 8
00310 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00311 start = end
00312 end += 4
00313 (length,) = _struct_I.unpack(str[start:end])
00314 start = end
00315 end += length
00316 self.action_result.status.goal_id.id = str[start:end]
00317 start = end
00318 end += 1
00319 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00320 start = end
00321 end += 4
00322 (length,) = _struct_I.unpack(str[start:end])
00323 start = end
00324 end += length
00325 self.action_result.status.text = str[start:end]
00326 _x = self
00327 start = end
00328 end += 57
00329 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.deformation, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.slip_detected, _x.action_result.result.data.deformation_limit_reached, _x.action_result.result.data.fingertip_force_limit_reached, _x.action_result.result.data.gripper_empty, _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_2I4d4Bb3I.unpack(str[start:end])
00330 self.action_result.result.data.slip_detected = bool(self.action_result.result.data.slip_detected)
00331 self.action_result.result.data.deformation_limit_reached = bool(self.action_result.result.data.deformation_limit_reached)
00332 self.action_result.result.data.fingertip_force_limit_reached = bool(self.action_result.result.data.fingertip_force_limit_reached)
00333 self.action_result.result.data.gripper_empty = bool(self.action_result.result.data.gripper_empty)
00334 start = end
00335 end += 4
00336 (length,) = _struct_I.unpack(str[start:end])
00337 start = end
00338 end += length
00339 self.action_feedback.header.frame_id = str[start:end]
00340 _x = self
00341 start = end
00342 end += 8
00343 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00344 start = end
00345 end += 4
00346 (length,) = _struct_I.unpack(str[start:end])
00347 start = end
00348 end += length
00349 self.action_feedback.status.goal_id.id = str[start:end]
00350 start = end
00351 end += 1
00352 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00353 start = end
00354 end += 4
00355 (length,) = _struct_I.unpack(str[start:end])
00356 start = end
00357 end += length
00358 self.action_feedback.status.text = str[start:end]
00359 _x = self
00360 start = end
00361 end += 45
00362 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.deformation, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.slip_detected, _x.action_feedback.feedback.data.deformation_limit_reached, _x.action_feedback.feedback.data.fingertip_force_limit_reached, _x.action_feedback.feedback.data.gripper_empty, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I4d4Bb.unpack(str[start:end])
00363 self.action_feedback.feedback.data.slip_detected = bool(self.action_feedback.feedback.data.slip_detected)
00364 self.action_feedback.feedback.data.deformation_limit_reached = bool(self.action_feedback.feedback.data.deformation_limit_reached)
00365 self.action_feedback.feedback.data.fingertip_force_limit_reached = bool(self.action_feedback.feedback.data.fingertip_force_limit_reached)
00366 self.action_feedback.feedback.data.gripper_empty = bool(self.action_feedback.feedback.data.gripper_empty)
00367 return self
00368 except struct.error, e:
00369 raise roslib.message.DeserializationError(e)
00370
00371
00372 def serialize_numpy(self, buff, numpy):
00373 """
00374 serialize message with numpy array types into buffer
00375 @param buff: buffer
00376 @type buff: StringIO
00377 @param numpy: numpy python module
00378 @type numpy module
00379 """
00380 try:
00381 _x = self
00382 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00383 _x = self.action_goal.header.frame_id
00384 length = len(_x)
00385 buff.write(struct.pack('<I%ss'%length, length, _x))
00386 _x = self
00387 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00388 _x = self.action_goal.goal_id.id
00389 length = len(_x)
00390 buff.write(struct.pack('<I%ss'%length, length, _x))
00391 _x = self
00392 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00393 _x = self.action_result.header.frame_id
00394 length = len(_x)
00395 buff.write(struct.pack('<I%ss'%length, length, _x))
00396 _x = self
00397 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00398 _x = self.action_result.status.goal_id.id
00399 length = len(_x)
00400 buff.write(struct.pack('<I%ss'%length, length, _x))
00401 buff.write(_struct_B.pack(self.action_result.status.status))
00402 _x = self.action_result.status.text
00403 length = len(_x)
00404 buff.write(struct.pack('<I%ss'%length, length, _x))
00405 _x = self
00406 buff.write(_struct_2I4d4Bb3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.deformation, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.slip_detected, _x.action_result.result.data.deformation_limit_reached, _x.action_result.result.data.fingertip_force_limit_reached, _x.action_result.result.data.gripper_empty, _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))
00407 _x = self.action_feedback.header.frame_id
00408 length = len(_x)
00409 buff.write(struct.pack('<I%ss'%length, length, _x))
00410 _x = self
00411 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00412 _x = self.action_feedback.status.goal_id.id
00413 length = len(_x)
00414 buff.write(struct.pack('<I%ss'%length, length, _x))
00415 buff.write(_struct_B.pack(self.action_feedback.status.status))
00416 _x = self.action_feedback.status.text
00417 length = len(_x)
00418 buff.write(struct.pack('<I%ss'%length, length, _x))
00419 _x = self
00420 buff.write(_struct_2I4d4Bb.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.deformation, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.slip_detected, _x.action_feedback.feedback.data.deformation_limit_reached, _x.action_feedback.feedback.data.fingertip_force_limit_reached, _x.action_feedback.feedback.data.gripper_empty, _x.action_feedback.feedback.data.rtstate.realtime_controller_state))
00421 except struct.error, se: self._check_types(se)
00422 except TypeError, te: self._check_types(te)
00423
00424 def deserialize_numpy(self, str, numpy):
00425 """
00426 unpack serialized message in str into this message instance using numpy for array types
00427 @param str: byte array of serialized message
00428 @type str: str
00429 @param numpy: numpy python module
00430 @type numpy: module
00431 """
00432 try:
00433 if self.action_goal is None:
00434 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionGoal()
00435 if self.action_result is None:
00436 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionResult()
00437 if self.action_feedback is None:
00438 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperSlipServoActionFeedback()
00439 end = 0
00440 _x = self
00441 start = end
00442 end += 12
00443 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00444 start = end
00445 end += 4
00446 (length,) = _struct_I.unpack(str[start:end])
00447 start = end
00448 end += length
00449 self.action_goal.header.frame_id = str[start:end]
00450 _x = self
00451 start = end
00452 end += 8
00453 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00454 start = end
00455 end += 4
00456 (length,) = _struct_I.unpack(str[start:end])
00457 start = end
00458 end += length
00459 self.action_goal.goal_id.id = str[start:end]
00460 _x = self
00461 start = end
00462 end += 12
00463 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00464 start = end
00465 end += 4
00466 (length,) = _struct_I.unpack(str[start:end])
00467 start = end
00468 end += length
00469 self.action_result.header.frame_id = str[start:end]
00470 _x = self
00471 start = end
00472 end += 8
00473 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00474 start = end
00475 end += 4
00476 (length,) = _struct_I.unpack(str[start:end])
00477 start = end
00478 end += length
00479 self.action_result.status.goal_id.id = str[start:end]
00480 start = end
00481 end += 1
00482 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00483 start = end
00484 end += 4
00485 (length,) = _struct_I.unpack(str[start:end])
00486 start = end
00487 end += length
00488 self.action_result.status.text = str[start:end]
00489 _x = self
00490 start = end
00491 end += 57
00492 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.deformation, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.slip_detected, _x.action_result.result.data.deformation_limit_reached, _x.action_result.result.data.fingertip_force_limit_reached, _x.action_result.result.data.gripper_empty, _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_2I4d4Bb3I.unpack(str[start:end])
00493 self.action_result.result.data.slip_detected = bool(self.action_result.result.data.slip_detected)
00494 self.action_result.result.data.deformation_limit_reached = bool(self.action_result.result.data.deformation_limit_reached)
00495 self.action_result.result.data.fingertip_force_limit_reached = bool(self.action_result.result.data.fingertip_force_limit_reached)
00496 self.action_result.result.data.gripper_empty = bool(self.action_result.result.data.gripper_empty)
00497 start = end
00498 end += 4
00499 (length,) = _struct_I.unpack(str[start:end])
00500 start = end
00501 end += length
00502 self.action_feedback.header.frame_id = str[start:end]
00503 _x = self
00504 start = end
00505 end += 8
00506 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00507 start = end
00508 end += 4
00509 (length,) = _struct_I.unpack(str[start:end])
00510 start = end
00511 end += length
00512 self.action_feedback.status.goal_id.id = str[start:end]
00513 start = end
00514 end += 1
00515 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00516 start = end
00517 end += 4
00518 (length,) = _struct_I.unpack(str[start:end])
00519 start = end
00520 end += length
00521 self.action_feedback.status.text = str[start:end]
00522 _x = self
00523 start = end
00524 end += 45
00525 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.deformation, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.slip_detected, _x.action_feedback.feedback.data.deformation_limit_reached, _x.action_feedback.feedback.data.fingertip_force_limit_reached, _x.action_feedback.feedback.data.gripper_empty, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I4d4Bb.unpack(str[start:end])
00526 self.action_feedback.feedback.data.slip_detected = bool(self.action_feedback.feedback.data.slip_detected)
00527 self.action_feedback.feedback.data.deformation_limit_reached = bool(self.action_feedback.feedback.data.deformation_limit_reached)
00528 self.action_feedback.feedback.data.fingertip_force_limit_reached = bool(self.action_feedback.feedback.data.fingertip_force_limit_reached)
00529 self.action_feedback.feedback.data.gripper_empty = bool(self.action_feedback.feedback.data.gripper_empty)
00530 return self
00531 except struct.error, e:
00532 raise roslib.message.DeserializationError(e)
00533
00534 _struct_I = roslib.message.struct_I
00535 _struct_2I4d4Bb3I = struct.Struct("<2I4d4Bb3I")
00536 _struct_3I = struct.Struct("<3I")
00537 _struct_B = struct.Struct("<B")
00538 _struct_2I = struct.Struct("<2I")
00539 _struct_2I4d4Bb = struct.Struct("<2I4d4Bb")