_PR2GripperFindContactData.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_gripper_sensor_msgs/PR2GripperFindContactData.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 pr2_gripper_sensor_msgs.msg
00009 
00010 class PR2GripperFindContactData(genpy.Message):
00011   _md5sum = "bc53e3dc7d19b896ca9b5ea205d54b91"
00012   _type = "pr2_gripper_sensor_msgs/PR2GripperFindContactData"
00013   _has_header = False #flag to mark the presence of a Header object
00014   _full_text = """# Time the data was recorded at
00015 time stamp
00016 
00017 # true when our contact conditions have been met
00018 # (see PR2GripperFindContact command)
00019 bool contact_conditions_met
00020 
00021 # the finger contact conditions 
00022 # true if the finger experienced a contact event
00023 #
00024 # contact events are defined as contact with the fingerpads
00025 # as either steady-state or high-freq force events
00026 bool left_fingertip_pad_contact
00027 bool right_fingertip_pad_contact
00028 
00029 # the force experinced by the finger Pads  (N)
00030 # NOTE:this ignores data from the edges of the finger pressure
00031 float64 left_fingertip_pad_force
00032 float64 right_fingertip_pad_force
00033 
00034 # the current joint position (m)
00035 float64 joint_position
00036 
00037 # the virtual (parallel) joint effort (N)
00038 float64 joint_effort
00039 
00040 # the control state of our realtime controller
00041 PR2GripperSensorRTState rtstate
00042 ================================================================================
00043 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState
00044 # the control state of our realtime controller
00045 int8 realtime_controller_state
00046 
00047 # predefined values to indicate our realtime_controller_state
00048 int8 DISABLED = 0
00049 int8 POSITION_SERVO = 3
00050 int8 FORCE_SERVO = 4
00051 int8 FIND_CONTACT = 5
00052 int8 SLIP_SERVO = 6
00053 """
00054   __slots__ = ['stamp','contact_conditions_met','left_fingertip_pad_contact','right_fingertip_pad_contact','left_fingertip_pad_force','right_fingertip_pad_force','joint_position','joint_effort','rtstate']
00055   _slot_types = ['time','bool','bool','bool','float64','float64','float64','float64','pr2_gripper_sensor_msgs/PR2GripperSensorRTState']
00056 
00057   def __init__(self, *args, **kwds):
00058     """
00059     Constructor. Any message fields that are implicitly/explicitly
00060     set to None will be assigned a default value. The recommend
00061     use is keyword arguments as this is more robust to future message
00062     changes.  You cannot mix in-order arguments and keyword arguments.
00063 
00064     The available fields are:
00065        stamp,contact_conditions_met,left_fingertip_pad_contact,right_fingertip_pad_contact,left_fingertip_pad_force,right_fingertip_pad_force,joint_position,joint_effort,rtstate
00066 
00067     :param args: complete set of field values, in .msg order
00068     :param kwds: use keyword arguments corresponding to message field names
00069     to set specific fields.
00070     """
00071     if args or kwds:
00072       super(PR2GripperFindContactData, self).__init__(*args, **kwds)
00073       #message fields cannot be None, assign default values for those that are
00074       if self.stamp is None:
00075         self.stamp = genpy.Time()
00076       if self.contact_conditions_met is None:
00077         self.contact_conditions_met = False
00078       if self.left_fingertip_pad_contact is None:
00079         self.left_fingertip_pad_contact = False
00080       if self.right_fingertip_pad_contact is None:
00081         self.right_fingertip_pad_contact = False
00082       if self.left_fingertip_pad_force is None:
00083         self.left_fingertip_pad_force = 0.
00084       if self.right_fingertip_pad_force is None:
00085         self.right_fingertip_pad_force = 0.
00086       if self.joint_position is None:
00087         self.joint_position = 0.
00088       if self.joint_effort is None:
00089         self.joint_effort = 0.
00090       if self.rtstate is None:
00091         self.rtstate = pr2_gripper_sensor_msgs.msg.PR2GripperSensorRTState()
00092     else:
00093       self.stamp = genpy.Time()
00094       self.contact_conditions_met = False
00095       self.left_fingertip_pad_contact = False
00096       self.right_fingertip_pad_contact = False
00097       self.left_fingertip_pad_force = 0.
00098       self.right_fingertip_pad_force = 0.
00099       self.joint_position = 0.
00100       self.joint_effort = 0.
00101       self.rtstate = pr2_gripper_sensor_msgs.msg.PR2GripperSensorRTState()
00102 
00103   def _get_types(self):
00104     """
00105     internal API method
00106     """
00107     return self._slot_types
00108 
00109   def serialize(self, buff):
00110     """
00111     serialize message into buffer
00112     :param buff: buffer, ``StringIO``
00113     """
00114     try:
00115       _x = self
00116       buff.write(_struct_2I3B4db.pack(_x.stamp.secs, _x.stamp.nsecs, _x.contact_conditions_met, _x.left_fingertip_pad_contact, _x.right_fingertip_pad_contact, _x.left_fingertip_pad_force, _x.right_fingertip_pad_force, _x.joint_position, _x.joint_effort, _x.rtstate.realtime_controller_state))
00117     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00118     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00119 
00120   def deserialize(self, str):
00121     """
00122     unpack serialized message in str into this message instance
00123     :param str: byte array of serialized message, ``str``
00124     """
00125     try:
00126       if self.stamp is None:
00127         self.stamp = genpy.Time()
00128       if self.rtstate is None:
00129         self.rtstate = pr2_gripper_sensor_msgs.msg.PR2GripperSensorRTState()
00130       end = 0
00131       _x = self
00132       start = end
00133       end += 44
00134       (_x.stamp.secs, _x.stamp.nsecs, _x.contact_conditions_met, _x.left_fingertip_pad_contact, _x.right_fingertip_pad_contact, _x.left_fingertip_pad_force, _x.right_fingertip_pad_force, _x.joint_position, _x.joint_effort, _x.rtstate.realtime_controller_state,) = _struct_2I3B4db.unpack(str[start:end])
00135       self.contact_conditions_met = bool(self.contact_conditions_met)
00136       self.left_fingertip_pad_contact = bool(self.left_fingertip_pad_contact)
00137       self.right_fingertip_pad_contact = bool(self.right_fingertip_pad_contact)
00138       self.stamp.canon()
00139       return self
00140     except struct.error as e:
00141       raise genpy.DeserializationError(e) #most likely buffer underfill
00142 
00143 
00144   def serialize_numpy(self, buff, numpy):
00145     """
00146     serialize message with numpy array types into buffer
00147     :param buff: buffer, ``StringIO``
00148     :param numpy: numpy python module
00149     """
00150     try:
00151       _x = self
00152       buff.write(_struct_2I3B4db.pack(_x.stamp.secs, _x.stamp.nsecs, _x.contact_conditions_met, _x.left_fingertip_pad_contact, _x.right_fingertip_pad_contact, _x.left_fingertip_pad_force, _x.right_fingertip_pad_force, _x.joint_position, _x.joint_effort, _x.rtstate.realtime_controller_state))
00153     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00154     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00155 
00156   def deserialize_numpy(self, str, numpy):
00157     """
00158     unpack serialized message in str into this message instance using numpy for array types
00159     :param str: byte array of serialized message, ``str``
00160     :param numpy: numpy python module
00161     """
00162     try:
00163       if self.stamp is None:
00164         self.stamp = genpy.Time()
00165       if self.rtstate is None:
00166         self.rtstate = pr2_gripper_sensor_msgs.msg.PR2GripperSensorRTState()
00167       end = 0
00168       _x = self
00169       start = end
00170       end += 44
00171       (_x.stamp.secs, _x.stamp.nsecs, _x.contact_conditions_met, _x.left_fingertip_pad_contact, _x.right_fingertip_pad_contact, _x.left_fingertip_pad_force, _x.right_fingertip_pad_force, _x.joint_position, _x.joint_effort, _x.rtstate.realtime_controller_state,) = _struct_2I3B4db.unpack(str[start:end])
00172       self.contact_conditions_met = bool(self.contact_conditions_met)
00173       self.left_fingertip_pad_contact = bool(self.left_fingertip_pad_contact)
00174       self.right_fingertip_pad_contact = bool(self.right_fingertip_pad_contact)
00175       self.stamp.canon()
00176       return self
00177     except struct.error as e:
00178       raise genpy.DeserializationError(e) #most likely buffer underfill
00179 
00180 _struct_I = genpy.struct_I
00181 _struct_2I3B4db = struct.Struct("<2I3B4db")


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