_PR2GripperForceServoAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_gripper_sensor_msgs/PR2GripperForceServoAction.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 PR2GripperForceServoAction(genpy.Message):
00013   _md5sum = "0540bb7603e65b3df5c9dc87b150e790"
00014   _type = "pr2_gripper_sensor_msgs/PR2GripperForceServoAction"
00015   _has_header = False #flag to mark the presence of a Header object
00016   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00017 
00018 PR2GripperForceServoActionGoal action_goal
00019 PR2GripperForceServoActionResult action_result
00020 PR2GripperForceServoActionFeedback action_feedback
00021 
00022 ================================================================================
00023 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionGoal
00024 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00025 
00026 Header header
00027 actionlib_msgs/GoalID goal_id
00028 PR2GripperForceServoGoal 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/PR2GripperForceServoGoal
00063 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00064 # Action to launch the gripper into force servoing mode 
00065 
00066 #goals
00067 PR2GripperForceServoCommand command
00068 
00069 ================================================================================
00070 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoCommand
00071 # the amount of fingertip force (in Newtons) to apply.
00072 # NOTE: the joint will squeeze until each finger reaches this level
00073 # values < 0 (opening force) are ignored
00074 #
00075 # 10 N can crack an egg or crush a soda can.
00076 # 15 N can firmly pick up a can of soup.
00077 # Experiment on your own.
00078 #
00079 float64 fingertip_force
00080 ================================================================================
00081 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionResult
00082 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00083 
00084 Header header
00085 actionlib_msgs/GoalStatus status
00086 PR2GripperForceServoResult result
00087 
00088 ================================================================================
00089 MSG: actionlib_msgs/GoalStatus
00090 GoalID goal_id
00091 uint8 status
00092 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00093 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00094 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00095                             #   and has since completed its execution (Terminal State)
00096 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00097 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00098                             #    to some failure (Terminal State)
00099 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00100                             #    because the goal was unattainable or invalid (Terminal State)
00101 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00102                             #    and has not yet completed execution
00103 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00104                             #    but the action server has not yet confirmed that the goal is canceled
00105 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00106                             #    and was successfully cancelled (Terminal State)
00107 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00108                             #    sent over the wire by an action server
00109 
00110 #Allow for the user to associate a string with GoalStatus for debugging
00111 string text
00112 
00113 
00114 ================================================================================
00115 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoResult
00116 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00117 
00118 #result
00119 PR2GripperForceServoData data
00120 
00121 
00122 ================================================================================
00123 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoData
00124 # Time the data was recorded at
00125 time stamp
00126 
00127 # the force experienced by the finger Pads  (N)
00128 # NOTE:this ignores data from the edges of the finger pressure
00129 float64 left_fingertip_pad_force
00130 float64 right_fingertip_pad_force
00131 
00132 # the current gripper virtual parallel joint effort (in N)
00133 float64 joint_effort
00134 
00135 # true when the gripper is no longer moving
00136 # and we have reached the desired force level
00137 bool force_achieved
00138 
00139 
00140 # the control state of our realtime controller
00141 PR2GripperSensorRTState rtstate
00142 
00143 ================================================================================
00144 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState
00145 # the control state of our realtime controller
00146 int8 realtime_controller_state
00147 
00148 # predefined values to indicate our realtime_controller_state
00149 int8 DISABLED = 0
00150 int8 POSITION_SERVO = 3
00151 int8 FORCE_SERVO = 4
00152 int8 FIND_CONTACT = 5
00153 int8 SLIP_SERVO = 6
00154 ================================================================================
00155 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionFeedback
00156 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00157 
00158 Header header
00159 actionlib_msgs/GoalStatus status
00160 PR2GripperForceServoFeedback feedback
00161 
00162 ================================================================================
00163 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoFeedback
00164 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00165 
00166 #feedback
00167 PR2GripperForceServoData data
00168 
00169 """
00170   __slots__ = ['action_goal','action_result','action_feedback']
00171   _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperForceServoActionGoal','pr2_gripper_sensor_msgs/PR2GripperForceServoActionResult','pr2_gripper_sensor_msgs/PR2GripperForceServoActionFeedback']
00172 
00173   def __init__(self, *args, **kwds):
00174     """
00175     Constructor. Any message fields that are implicitly/explicitly
00176     set to None will be assigned a default value. The recommend
00177     use is keyword arguments as this is more robust to future message
00178     changes.  You cannot mix in-order arguments and keyword arguments.
00179 
00180     The available fields are:
00181        action_goal,action_result,action_feedback
00182 
00183     :param args: complete set of field values, in .msg order
00184     :param kwds: use keyword arguments corresponding to message field names
00185     to set specific fields.
00186     """
00187     if args or kwds:
00188       super(PR2GripperForceServoAction, self).__init__(*args, **kwds)
00189       #message fields cannot be None, assign default values for those that are
00190       if self.action_goal is None:
00191         self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal()
00192       if self.action_result is None:
00193         self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult()
00194       if self.action_feedback is None:
00195         self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback()
00196     else:
00197       self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal()
00198       self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult()
00199       self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback()
00200 
00201   def _get_types(self):
00202     """
00203     internal API method
00204     """
00205     return self._slot_types
00206 
00207   def serialize(self, buff):
00208     """
00209     serialize message into buffer
00210     :param buff: buffer, ``StringIO``
00211     """
00212     try:
00213       _x = self
00214       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00215       _x = self.action_goal.header.frame_id
00216       length = len(_x)
00217       if python3 or type(_x) == unicode:
00218         _x = _x.encode('utf-8')
00219         length = len(_x)
00220       buff.write(struct.pack('<I%ss'%length, length, _x))
00221       _x = self
00222       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00223       _x = self.action_goal.goal_id.id
00224       length = len(_x)
00225       if python3 or type(_x) == unicode:
00226         _x = _x.encode('utf-8')
00227         length = len(_x)
00228       buff.write(struct.pack('<I%ss'%length, length, _x))
00229       _x = self
00230       buff.write(_struct_d3I.pack(_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00231       _x = self.action_result.header.frame_id
00232       length = len(_x)
00233       if python3 or type(_x) == unicode:
00234         _x = _x.encode('utf-8')
00235         length = len(_x)
00236       buff.write(struct.pack('<I%ss'%length, length, _x))
00237       _x = self
00238       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00239       _x = self.action_result.status.goal_id.id
00240       length = len(_x)
00241       if python3 or type(_x) == unicode:
00242         _x = _x.encode('utf-8')
00243         length = len(_x)
00244       buff.write(struct.pack('<I%ss'%length, length, _x))
00245       buff.write(_struct_B.pack(self.action_result.status.status))
00246       _x = self.action_result.status.text
00247       length = len(_x)
00248       if python3 or type(_x) == unicode:
00249         _x = _x.encode('utf-8')
00250         length = len(_x)
00251       buff.write(struct.pack('<I%ss'%length, length, _x))
00252       _x = self
00253       buff.write(_struct_2I3dBb3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _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.force_achieved, _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))
00254       _x = self.action_feedback.header.frame_id
00255       length = len(_x)
00256       if python3 or type(_x) == unicode:
00257         _x = _x.encode('utf-8')
00258         length = len(_x)
00259       buff.write(struct.pack('<I%ss'%length, length, _x))
00260       _x = self
00261       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00262       _x = self.action_feedback.status.goal_id.id
00263       length = len(_x)
00264       if python3 or type(_x) == unicode:
00265         _x = _x.encode('utf-8')
00266         length = len(_x)
00267       buff.write(struct.pack('<I%ss'%length, length, _x))
00268       buff.write(_struct_B.pack(self.action_feedback.status.status))
00269       _x = self.action_feedback.status.text
00270       length = len(_x)
00271       if python3 or type(_x) == unicode:
00272         _x = _x.encode('utf-8')
00273         length = len(_x)
00274       buff.write(struct.pack('<I%ss'%length, length, _x))
00275       _x = self
00276       buff.write(_struct_2I3dBb.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _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.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state))
00277     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00278     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00279 
00280   def deserialize(self, str):
00281     """
00282     unpack serialized message in str into this message instance
00283     :param str: byte array of serialized message, ``str``
00284     """
00285     try:
00286       if self.action_goal is None:
00287         self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal()
00288       if self.action_result is None:
00289         self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult()
00290       if self.action_feedback is None:
00291         self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback()
00292       end = 0
00293       _x = self
00294       start = end
00295       end += 12
00296       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00297       start = end
00298       end += 4
00299       (length,) = _struct_I.unpack(str[start:end])
00300       start = end
00301       end += length
00302       if python3:
00303         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00304       else:
00305         self.action_goal.header.frame_id = str[start:end]
00306       _x = self
00307       start = end
00308       end += 8
00309       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00310       start = end
00311       end += 4
00312       (length,) = _struct_I.unpack(str[start:end])
00313       start = end
00314       end += length
00315       if python3:
00316         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00317       else:
00318         self.action_goal.goal_id.id = str[start:end]
00319       _x = self
00320       start = end
00321       end += 20
00322       (_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end])
00323       start = end
00324       end += 4
00325       (length,) = _struct_I.unpack(str[start:end])
00326       start = end
00327       end += length
00328       if python3:
00329         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00330       else:
00331         self.action_result.header.frame_id = str[start:end]
00332       _x = self
00333       start = end
00334       end += 8
00335       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00336       start = end
00337       end += 4
00338       (length,) = _struct_I.unpack(str[start:end])
00339       start = end
00340       end += length
00341       if python3:
00342         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00343       else:
00344         self.action_result.status.goal_id.id = str[start:end]
00345       start = end
00346       end += 1
00347       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00348       start = end
00349       end += 4
00350       (length,) = _struct_I.unpack(str[start:end])
00351       start = end
00352       end += length
00353       if python3:
00354         self.action_result.status.text = str[start:end].decode('utf-8')
00355       else:
00356         self.action_result.status.text = str[start:end]
00357       _x = self
00358       start = end
00359       end += 46
00360       (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _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.force_achieved, _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_2I3dBb3I.unpack(str[start:end])
00361       self.action_result.result.data.force_achieved = bool(self.action_result.result.data.force_achieved)
00362       start = end
00363       end += 4
00364       (length,) = _struct_I.unpack(str[start:end])
00365       start = end
00366       end += length
00367       if python3:
00368         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00369       else:
00370         self.action_feedback.header.frame_id = str[start:end]
00371       _x = self
00372       start = end
00373       end += 8
00374       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00375       start = end
00376       end += 4
00377       (length,) = _struct_I.unpack(str[start:end])
00378       start = end
00379       end += length
00380       if python3:
00381         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00382       else:
00383         self.action_feedback.status.goal_id.id = str[start:end]
00384       start = end
00385       end += 1
00386       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00387       start = end
00388       end += 4
00389       (length,) = _struct_I.unpack(str[start:end])
00390       start = end
00391       end += length
00392       if python3:
00393         self.action_feedback.status.text = str[start:end].decode('utf-8')
00394       else:
00395         self.action_feedback.status.text = str[start:end]
00396       _x = self
00397       start = end
00398       end += 34
00399       (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _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.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3dBb.unpack(str[start:end])
00400       self.action_feedback.feedback.data.force_achieved = bool(self.action_feedback.feedback.data.force_achieved)
00401       return self
00402     except struct.error as e:
00403       raise genpy.DeserializationError(e) #most likely buffer underfill
00404 
00405 
00406   def serialize_numpy(self, buff, numpy):
00407     """
00408     serialize message with numpy array types into buffer
00409     :param buff: buffer, ``StringIO``
00410     :param numpy: numpy python module
00411     """
00412     try:
00413       _x = self
00414       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00415       _x = self.action_goal.header.frame_id
00416       length = len(_x)
00417       if python3 or type(_x) == unicode:
00418         _x = _x.encode('utf-8')
00419         length = len(_x)
00420       buff.write(struct.pack('<I%ss'%length, length, _x))
00421       _x = self
00422       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00423       _x = self.action_goal.goal_id.id
00424       length = len(_x)
00425       if python3 or type(_x) == unicode:
00426         _x = _x.encode('utf-8')
00427         length = len(_x)
00428       buff.write(struct.pack('<I%ss'%length, length, _x))
00429       _x = self
00430       buff.write(_struct_d3I.pack(_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00431       _x = self.action_result.header.frame_id
00432       length = len(_x)
00433       if python3 or type(_x) == unicode:
00434         _x = _x.encode('utf-8')
00435         length = len(_x)
00436       buff.write(struct.pack('<I%ss'%length, length, _x))
00437       _x = self
00438       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00439       _x = self.action_result.status.goal_id.id
00440       length = len(_x)
00441       if python3 or type(_x) == unicode:
00442         _x = _x.encode('utf-8')
00443         length = len(_x)
00444       buff.write(struct.pack('<I%ss'%length, length, _x))
00445       buff.write(_struct_B.pack(self.action_result.status.status))
00446       _x = self.action_result.status.text
00447       length = len(_x)
00448       if python3 or type(_x) == unicode:
00449         _x = _x.encode('utf-8')
00450         length = len(_x)
00451       buff.write(struct.pack('<I%ss'%length, length, _x))
00452       _x = self
00453       buff.write(_struct_2I3dBb3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _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.force_achieved, _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))
00454       _x = self.action_feedback.header.frame_id
00455       length = len(_x)
00456       if python3 or type(_x) == unicode:
00457         _x = _x.encode('utf-8')
00458         length = len(_x)
00459       buff.write(struct.pack('<I%ss'%length, length, _x))
00460       _x = self
00461       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00462       _x = self.action_feedback.status.goal_id.id
00463       length = len(_x)
00464       if python3 or type(_x) == unicode:
00465         _x = _x.encode('utf-8')
00466         length = len(_x)
00467       buff.write(struct.pack('<I%ss'%length, length, _x))
00468       buff.write(_struct_B.pack(self.action_feedback.status.status))
00469       _x = self.action_feedback.status.text
00470       length = len(_x)
00471       if python3 or type(_x) == unicode:
00472         _x = _x.encode('utf-8')
00473         length = len(_x)
00474       buff.write(struct.pack('<I%ss'%length, length, _x))
00475       _x = self
00476       buff.write(_struct_2I3dBb.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _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.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state))
00477     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00478     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00479 
00480   def deserialize_numpy(self, str, numpy):
00481     """
00482     unpack serialized message in str into this message instance using numpy for array types
00483     :param str: byte array of serialized message, ``str``
00484     :param numpy: numpy python module
00485     """
00486     try:
00487       if self.action_goal is None:
00488         self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal()
00489       if self.action_result is None:
00490         self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult()
00491       if self.action_feedback is None:
00492         self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback()
00493       end = 0
00494       _x = self
00495       start = end
00496       end += 12
00497       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00498       start = end
00499       end += 4
00500       (length,) = _struct_I.unpack(str[start:end])
00501       start = end
00502       end += length
00503       if python3:
00504         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00505       else:
00506         self.action_goal.header.frame_id = str[start:end]
00507       _x = self
00508       start = end
00509       end += 8
00510       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00511       start = end
00512       end += 4
00513       (length,) = _struct_I.unpack(str[start:end])
00514       start = end
00515       end += length
00516       if python3:
00517         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00518       else:
00519         self.action_goal.goal_id.id = str[start:end]
00520       _x = self
00521       start = end
00522       end += 20
00523       (_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end])
00524       start = end
00525       end += 4
00526       (length,) = _struct_I.unpack(str[start:end])
00527       start = end
00528       end += length
00529       if python3:
00530         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00531       else:
00532         self.action_result.header.frame_id = str[start:end]
00533       _x = self
00534       start = end
00535       end += 8
00536       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00537       start = end
00538       end += 4
00539       (length,) = _struct_I.unpack(str[start:end])
00540       start = end
00541       end += length
00542       if python3:
00543         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00544       else:
00545         self.action_result.status.goal_id.id = str[start:end]
00546       start = end
00547       end += 1
00548       (self.action_result.status.status,) = _struct_B.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.text = str[start:end].decode('utf-8')
00556       else:
00557         self.action_result.status.text = str[start:end]
00558       _x = self
00559       start = end
00560       end += 46
00561       (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _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.force_achieved, _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_2I3dBb3I.unpack(str[start:end])
00562       self.action_result.result.data.force_achieved = bool(self.action_result.result.data.force_achieved)
00563       start = end
00564       end += 4
00565       (length,) = _struct_I.unpack(str[start:end])
00566       start = end
00567       end += length
00568       if python3:
00569         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00570       else:
00571         self.action_feedback.header.frame_id = str[start:end]
00572       _x = self
00573       start = end
00574       end += 8
00575       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00576       start = end
00577       end += 4
00578       (length,) = _struct_I.unpack(str[start:end])
00579       start = end
00580       end += length
00581       if python3:
00582         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00583       else:
00584         self.action_feedback.status.goal_id.id = str[start:end]
00585       start = end
00586       end += 1
00587       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00588       start = end
00589       end += 4
00590       (length,) = _struct_I.unpack(str[start:end])
00591       start = end
00592       end += length
00593       if python3:
00594         self.action_feedback.status.text = str[start:end].decode('utf-8')
00595       else:
00596         self.action_feedback.status.text = str[start:end]
00597       _x = self
00598       start = end
00599       end += 34
00600       (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _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.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3dBb.unpack(str[start:end])
00601       self.action_feedback.feedback.data.force_achieved = bool(self.action_feedback.feedback.data.force_achieved)
00602       return self
00603     except struct.error as e:
00604       raise genpy.DeserializationError(e) #most likely buffer underfill
00605 
00606 _struct_I = genpy.struct_I
00607 _struct_B = struct.Struct("<B")
00608 _struct_3I = struct.Struct("<3I")
00609 _struct_2I3dBb3I = struct.Struct("<2I3dBb3I")
00610 _struct_d3I = struct.Struct("<d3I")
00611 _struct_2I3dBb = struct.Struct("<2I3dBb")
00612 _struct_2I = struct.Struct("<2I")


pr2_gripper_sensor_msgs
Author(s): Joe Romano
autogenerated on Mon Oct 6 2014 12:17:32