00001 """autogenerated by genmsg_py from PR2GripperFindContactAction.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 PR2GripperFindContactAction(roslib.message.Message):
00011 _md5sum = "99ab2df1bbde46c447b38f28b7896d16"
00012 _type = "pr2_gripper_sensor_msgs/PR2GripperFindContactAction"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015
00016 PR2GripperFindContactActionGoal action_goal
00017 PR2GripperFindContactActionResult action_result
00018 PR2GripperFindContactActionFeedback action_feedback
00019
00020 ================================================================================
00021 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactActionGoal
00022 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00023
00024 Header header
00025 actionlib_msgs/GoalID goal_id
00026 PR2GripperFindContactGoal 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/PR2GripperFindContactGoal
00061 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00062 # Contact action used to close fingers and find object contacts
00063 # quickly while still stopping fast in real-time to not damage
00064 # objects
00065
00066 #goal
00067 PR2GripperFindContactCommand command
00068
00069 ================================================================================
00070 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactCommand
00071 # set true if you want to calibrate the fingertip sensors on the start
00072 # of the find_contact action. While this is not necessary (and
00073 # the default value will not calibrate the sensors) for best
00074 # performance it is recommended that you set this to true each time
00075 # you are calling find_contact and are confident the fingertips are
00076 # not touching anything
00077 # NOTE: SHOULD ONLY BE TRUE WHEN BOTH FINGERS ARE TOUCHING NOTHING
00078 bool zero_fingertip_sensors
00079
00080 # the finger contact conditions that determine what our goal is
00081 # Leaving this field blank will result in the robot closing until
00082 # contact on BOTH fingers is achieved
00083 int8 contact_conditions
00084
00085 # predefined values for the above contact_conditions variable
00086 int8 BOTH = 0 # both fingers must make contact
00087 int8 LEFT = 1 # just the left finger
00088 int8 RIGHT = 2 # just the right finger
00089 int8 EITHER = 3 # either finger, we don't care which
00090
00091 ================================================================================
00092 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactActionResult
00093 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00094
00095 Header header
00096 actionlib_msgs/GoalStatus status
00097 PR2GripperFindContactResult result
00098
00099 ================================================================================
00100 MSG: actionlib_msgs/GoalStatus
00101 GoalID goal_id
00102 uint8 status
00103 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00104 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00105 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00106 # and has since completed its execution (Terminal State)
00107 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00108 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00109 # to some failure (Terminal State)
00110 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00111 # because the goal was unattainable or invalid (Terminal State)
00112 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00113 # and has not yet completed execution
00114 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00115 # but the action server has not yet confirmed that the goal is canceled
00116 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00117 # and was successfully cancelled (Terminal State)
00118 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00119 # sent over the wire by an action server
00120
00121 #Allow for the user to associate a string with GoalStatus for debugging
00122 string text
00123
00124
00125 ================================================================================
00126 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactResult
00127 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00128 #results
00129 PR2GripperFindContactData data
00130
00131 ================================================================================
00132 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactData
00133 # Time the data was recorded at
00134 time stamp
00135
00136 # true when our contact conditions have been met
00137 # (see PR2GripperFindContact command)
00138 bool contact_conditions_met
00139
00140 # the finger contact conditions
00141 # true if the finger experienced a contact event
00142 #
00143 # contact events are defined as contact with the fingerpads
00144 # as either steady-state or high-freq force events
00145 bool left_fingertip_pad_contact
00146 bool right_fingertip_pad_contact
00147
00148 # the force experinced by the finger Pads (N)
00149 # NOTE:this ignores data from the edges of the finger pressure
00150 float64 left_fingertip_pad_force
00151 float64 right_fingertip_pad_force
00152
00153 # the current joint position (m)
00154 float64 joint_position
00155
00156 # the virtual (parallel) joint effort (N)
00157 float64 joint_effort
00158
00159 # the control state of our realtime controller
00160 PR2GripperSensorRTState rtstate
00161 ================================================================================
00162 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState
00163 # the control state of our realtime controller
00164 int8 realtime_controller_state
00165
00166 # predefined values to indicate our realtime_controller_state
00167 int8 DISABLED = 0
00168 int8 POSITION_SERVO = 3
00169 int8 FORCE_SERVO = 4
00170 int8 FIND_CONTACT = 5
00171 int8 SLIP_SERVO = 6
00172 ================================================================================
00173 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactActionFeedback
00174 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00175
00176 Header header
00177 actionlib_msgs/GoalStatus status
00178 PR2GripperFindContactFeedback feedback
00179
00180 ================================================================================
00181 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactFeedback
00182 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00183 # feedback
00184 PR2GripperFindContactData data
00185
00186
00187
00188 """
00189 __slots__ = ['action_goal','action_result','action_feedback']
00190 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperFindContactActionGoal','pr2_gripper_sensor_msgs/PR2GripperFindContactActionResult','pr2_gripper_sensor_msgs/PR2GripperFindContactActionFeedback']
00191
00192 def __init__(self, *args, **kwds):
00193 """
00194 Constructor. Any message fields that are implicitly/explicitly
00195 set to None will be assigned a default value. The recommend
00196 use is keyword arguments as this is more robust to future message
00197 changes. You cannot mix in-order arguments and keyword arguments.
00198
00199 The available fields are:
00200 action_goal,action_result,action_feedback
00201
00202 @param args: complete set of field values, in .msg order
00203 @param kwds: use keyword arguments corresponding to message field names
00204 to set specific fields.
00205 """
00206 if args or kwds:
00207 super(PR2GripperFindContactAction, self).__init__(*args, **kwds)
00208
00209 if self.action_goal is None:
00210 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionGoal()
00211 if self.action_result is None:
00212 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionResult()
00213 if self.action_feedback is None:
00214 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionFeedback()
00215 else:
00216 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionGoal()
00217 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionResult()
00218 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionFeedback()
00219
00220 def _get_types(self):
00221 """
00222 internal API method
00223 """
00224 return self._slot_types
00225
00226 def serialize(self, buff):
00227 """
00228 serialize message into buffer
00229 @param buff: buffer
00230 @type buff: StringIO
00231 """
00232 try:
00233 _x = self
00234 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00235 _x = self.action_goal.header.frame_id
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 buff.write(struct.pack('<I%ss'%length, length, _x))
00243 _x = self
00244 buff.write(_struct_Bb3I.pack(_x.action_goal.goal.command.zero_fingertip_sensors, _x.action_goal.goal.command.contact_conditions, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00245 _x = self.action_result.header.frame_id
00246 length = len(_x)
00247 buff.write(struct.pack('<I%ss'%length, length, _x))
00248 _x = self
00249 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00250 _x = self.action_result.status.goal_id.id
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 buff.write(_struct_B.pack(self.action_result.status.status))
00254 _x = self.action_result.status.text
00255 length = len(_x)
00256 buff.write(struct.pack('<I%ss'%length, length, _x))
00257 _x = self
00258 buff.write(_struct_2I3B4db3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.contact_conditions_met, _x.action_result.result.data.left_fingertip_pad_contact, _x.action_result.result.data.right_fingertip_pad_contact, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_position, _x.action_result.result.data.joint_effort, _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))
00259 _x = self.action_feedback.header.frame_id
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 _x = self
00263 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00264 _x = self.action_feedback.status.goal_id.id
00265 length = len(_x)
00266 buff.write(struct.pack('<I%ss'%length, length, _x))
00267 buff.write(_struct_B.pack(self.action_feedback.status.status))
00268 _x = self.action_feedback.status.text
00269 length = len(_x)
00270 buff.write(struct.pack('<I%ss'%length, length, _x))
00271 _x = self
00272 buff.write(_struct_2I3B4db.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.contact_conditions_met, _x.action_feedback.feedback.data.left_fingertip_pad_contact, _x.action_feedback.feedback.data.right_fingertip_pad_contact, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_position, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.rtstate.realtime_controller_state))
00273 except struct.error, se: self._check_types(se)
00274 except TypeError, te: self._check_types(te)
00275
00276 def deserialize(self, str):
00277 """
00278 unpack serialized message in str into this message instance
00279 @param str: byte array of serialized message
00280 @type str: str
00281 """
00282 try:
00283 if self.action_goal is None:
00284 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionGoal()
00285 if self.action_result is None:
00286 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionResult()
00287 if self.action_feedback is None:
00288 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionFeedback()
00289 end = 0
00290 _x = self
00291 start = end
00292 end += 12
00293 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00294 start = end
00295 end += 4
00296 (length,) = _struct_I.unpack(str[start:end])
00297 start = end
00298 end += length
00299 self.action_goal.header.frame_id = str[start:end]
00300 _x = self
00301 start = end
00302 end += 8
00303 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00304 start = end
00305 end += 4
00306 (length,) = _struct_I.unpack(str[start:end])
00307 start = end
00308 end += length
00309 self.action_goal.goal_id.id = str[start:end]
00310 _x = self
00311 start = end
00312 end += 14
00313 (_x.action_goal.goal.command.zero_fingertip_sensors, _x.action_goal.goal.command.contact_conditions, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_Bb3I.unpack(str[start:end])
00314 self.action_goal.goal.command.zero_fingertip_sensors = bool(self.action_goal.goal.command.zero_fingertip_sensors)
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 start = end
00319 end += length
00320 self.action_result.header.frame_id = str[start:end]
00321 _x = self
00322 start = end
00323 end += 8
00324 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00325 start = end
00326 end += 4
00327 (length,) = _struct_I.unpack(str[start:end])
00328 start = end
00329 end += length
00330 self.action_result.status.goal_id.id = str[start:end]
00331 start = end
00332 end += 1
00333 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00334 start = end
00335 end += 4
00336 (length,) = _struct_I.unpack(str[start:end])
00337 start = end
00338 end += length
00339 self.action_result.status.text = str[start:end]
00340 _x = self
00341 start = end
00342 end += 56
00343 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.contact_conditions_met, _x.action_result.result.data.left_fingertip_pad_contact, _x.action_result.result.data.right_fingertip_pad_contact, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_position, _x.action_result.result.data.joint_effort, _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_2I3B4db3I.unpack(str[start:end])
00344 self.action_result.result.data.contact_conditions_met = bool(self.action_result.result.data.contact_conditions_met)
00345 self.action_result.result.data.left_fingertip_pad_contact = bool(self.action_result.result.data.left_fingertip_pad_contact)
00346 self.action_result.result.data.right_fingertip_pad_contact = bool(self.action_result.result.data.right_fingertip_pad_contact)
00347 start = end
00348 end += 4
00349 (length,) = _struct_I.unpack(str[start:end])
00350 start = end
00351 end += length
00352 self.action_feedback.header.frame_id = str[start:end]
00353 _x = self
00354 start = end
00355 end += 8
00356 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00357 start = end
00358 end += 4
00359 (length,) = _struct_I.unpack(str[start:end])
00360 start = end
00361 end += length
00362 self.action_feedback.status.goal_id.id = str[start:end]
00363 start = end
00364 end += 1
00365 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00366 start = end
00367 end += 4
00368 (length,) = _struct_I.unpack(str[start:end])
00369 start = end
00370 end += length
00371 self.action_feedback.status.text = str[start:end]
00372 _x = self
00373 start = end
00374 end += 44
00375 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.contact_conditions_met, _x.action_feedback.feedback.data.left_fingertip_pad_contact, _x.action_feedback.feedback.data.right_fingertip_pad_contact, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_position, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3B4db.unpack(str[start:end])
00376 self.action_feedback.feedback.data.contact_conditions_met = bool(self.action_feedback.feedback.data.contact_conditions_met)
00377 self.action_feedback.feedback.data.left_fingertip_pad_contact = bool(self.action_feedback.feedback.data.left_fingertip_pad_contact)
00378 self.action_feedback.feedback.data.right_fingertip_pad_contact = bool(self.action_feedback.feedback.data.right_fingertip_pad_contact)
00379 return self
00380 except struct.error, e:
00381 raise roslib.message.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
00388 @type buff: StringIO
00389 @param numpy: numpy python module
00390 @type numpy module
00391 """
00392 try:
00393 _x = self
00394 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00395 _x = self.action_goal.header.frame_id
00396 length = len(_x)
00397 buff.write(struct.pack('<I%ss'%length, length, _x))
00398 _x = self
00399 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00400 _x = self.action_goal.goal_id.id
00401 length = len(_x)
00402 buff.write(struct.pack('<I%ss'%length, length, _x))
00403 _x = self
00404 buff.write(_struct_Bb3I.pack(_x.action_goal.goal.command.zero_fingertip_sensors, _x.action_goal.goal.command.contact_conditions, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00405 _x = self.action_result.header.frame_id
00406 length = len(_x)
00407 buff.write(struct.pack('<I%ss'%length, length, _x))
00408 _x = self
00409 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00410 _x = self.action_result.status.goal_id.id
00411 length = len(_x)
00412 buff.write(struct.pack('<I%ss'%length, length, _x))
00413 buff.write(_struct_B.pack(self.action_result.status.status))
00414 _x = self.action_result.status.text
00415 length = len(_x)
00416 buff.write(struct.pack('<I%ss'%length, length, _x))
00417 _x = self
00418 buff.write(_struct_2I3B4db3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.contact_conditions_met, _x.action_result.result.data.left_fingertip_pad_contact, _x.action_result.result.data.right_fingertip_pad_contact, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_position, _x.action_result.result.data.joint_effort, _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))
00419 _x = self.action_feedback.header.frame_id
00420 length = len(_x)
00421 buff.write(struct.pack('<I%ss'%length, length, _x))
00422 _x = self
00423 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00424 _x = self.action_feedback.status.goal_id.id
00425 length = len(_x)
00426 buff.write(struct.pack('<I%ss'%length, length, _x))
00427 buff.write(_struct_B.pack(self.action_feedback.status.status))
00428 _x = self.action_feedback.status.text
00429 length = len(_x)
00430 buff.write(struct.pack('<I%ss'%length, length, _x))
00431 _x = self
00432 buff.write(_struct_2I3B4db.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.contact_conditions_met, _x.action_feedback.feedback.data.left_fingertip_pad_contact, _x.action_feedback.feedback.data.right_fingertip_pad_contact, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_position, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.rtstate.realtime_controller_state))
00433 except struct.error, se: self._check_types(se)
00434 except TypeError, te: self._check_types(te)
00435
00436 def deserialize_numpy(self, str, numpy):
00437 """
00438 unpack serialized message in str into this message instance using numpy for array types
00439 @param str: byte array of serialized message
00440 @type str: str
00441 @param numpy: numpy python module
00442 @type numpy: module
00443 """
00444 try:
00445 if self.action_goal is None:
00446 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionGoal()
00447 if self.action_result is None:
00448 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionResult()
00449 if self.action_feedback is None:
00450 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactActionFeedback()
00451 end = 0
00452 _x = self
00453 start = end
00454 end += 12
00455 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00456 start = end
00457 end += 4
00458 (length,) = _struct_I.unpack(str[start:end])
00459 start = end
00460 end += length
00461 self.action_goal.header.frame_id = str[start:end]
00462 _x = self
00463 start = end
00464 end += 8
00465 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00466 start = end
00467 end += 4
00468 (length,) = _struct_I.unpack(str[start:end])
00469 start = end
00470 end += length
00471 self.action_goal.goal_id.id = str[start:end]
00472 _x = self
00473 start = end
00474 end += 14
00475 (_x.action_goal.goal.command.zero_fingertip_sensors, _x.action_goal.goal.command.contact_conditions, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_Bb3I.unpack(str[start:end])
00476 self.action_goal.goal.command.zero_fingertip_sensors = bool(self.action_goal.goal.command.zero_fingertip_sensors)
00477 start = end
00478 end += 4
00479 (length,) = _struct_I.unpack(str[start:end])
00480 start = end
00481 end += length
00482 self.action_result.header.frame_id = str[start:end]
00483 _x = self
00484 start = end
00485 end += 8
00486 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00487 start = end
00488 end += 4
00489 (length,) = _struct_I.unpack(str[start:end])
00490 start = end
00491 end += length
00492 self.action_result.status.goal_id.id = str[start:end]
00493 start = end
00494 end += 1
00495 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00496 start = end
00497 end += 4
00498 (length,) = _struct_I.unpack(str[start:end])
00499 start = end
00500 end += length
00501 self.action_result.status.text = str[start:end]
00502 _x = self
00503 start = end
00504 end += 56
00505 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.contact_conditions_met, _x.action_result.result.data.left_fingertip_pad_contact, _x.action_result.result.data.right_fingertip_pad_contact, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_position, _x.action_result.result.data.joint_effort, _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_2I3B4db3I.unpack(str[start:end])
00506 self.action_result.result.data.contact_conditions_met = bool(self.action_result.result.data.contact_conditions_met)
00507 self.action_result.result.data.left_fingertip_pad_contact = bool(self.action_result.result.data.left_fingertip_pad_contact)
00508 self.action_result.result.data.right_fingertip_pad_contact = bool(self.action_result.result.data.right_fingertip_pad_contact)
00509 start = end
00510 end += 4
00511 (length,) = _struct_I.unpack(str[start:end])
00512 start = end
00513 end += length
00514 self.action_feedback.header.frame_id = str[start:end]
00515 _x = self
00516 start = end
00517 end += 8
00518 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00519 start = end
00520 end += 4
00521 (length,) = _struct_I.unpack(str[start:end])
00522 start = end
00523 end += length
00524 self.action_feedback.status.goal_id.id = str[start:end]
00525 start = end
00526 end += 1
00527 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00528 start = end
00529 end += 4
00530 (length,) = _struct_I.unpack(str[start:end])
00531 start = end
00532 end += length
00533 self.action_feedback.status.text = str[start:end]
00534 _x = self
00535 start = end
00536 end += 44
00537 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.contact_conditions_met, _x.action_feedback.feedback.data.left_fingertip_pad_contact, _x.action_feedback.feedback.data.right_fingertip_pad_contact, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_position, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3B4db.unpack(str[start:end])
00538 self.action_feedback.feedback.data.contact_conditions_met = bool(self.action_feedback.feedback.data.contact_conditions_met)
00539 self.action_feedback.feedback.data.left_fingertip_pad_contact = bool(self.action_feedback.feedback.data.left_fingertip_pad_contact)
00540 self.action_feedback.feedback.data.right_fingertip_pad_contact = bool(self.action_feedback.feedback.data.right_fingertip_pad_contact)
00541 return self
00542 except struct.error, e:
00543 raise roslib.message.DeserializationError(e)
00544
00545 _struct_I = roslib.message.struct_I
00546 _struct_B = struct.Struct("<B")
00547 _struct_2I3B4db = struct.Struct("<2I3B4db")
00548 _struct_Bb3I = struct.Struct("<Bb3I")
00549 _struct_3I = struct.Struct("<3I")
00550 _struct_2I = struct.Struct("<2I")
00551 _struct_2I3B4db3I = struct.Struct("<2I3B4db3I")