00001 """autogenerated by genpy from pr2_gripper_sensor_msgs/PR2GripperEventDetectorFeedback.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 PR2GripperEventDetectorFeedback(genpy.Message):
00011 _md5sum = "817b45a51c75a067eb5dfb8e18b14aa1"
00012 _type = "pr2_gripper_sensor_msgs/PR2GripperEventDetectorFeedback"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015 # feedback
00016 PR2GripperEventDetectorData data
00017
00018
00019
00020 ================================================================================
00021 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorData
00022 # Time the data was recorded at
00023 time stamp
00024
00025 # true if the trigger conditions have been met
00026 # (see PR2GripperEventDetectorCommand)
00027 bool trigger_conditions_met
00028
00029 # true if the pressure sensors detected a slip event
00030 # slip events occur when the finger pressure sensors
00031 # high-freq. content exceeds the slip_trigger_magnitude variable
00032 # (see PR2GripperEventDetectorCommand)
00033 bool slip_event
00034
00035 # true if the hand-mounted accelerometer detected a contact acceleration
00036 # acceleration events occur when the palm accelerometer
00037 # high-freq. content exceeds the acc_trigger_magnitude variable
00038 # (see PR2GripperEventDetectorCommand)
00039 bool acceleration_event
00040
00041 # the high-freq acceleration vector that was last seen (x,y,z)
00042 float64[3] acceleration_vector
00043 """
00044 __slots__ = ['data']
00045 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperEventDetectorData']
00046
00047 def __init__(self, *args, **kwds):
00048 """
00049 Constructor. Any message fields that are implicitly/explicitly
00050 set to None will be assigned a default value. The recommend
00051 use is keyword arguments as this is more robust to future message
00052 changes. You cannot mix in-order arguments and keyword arguments.
00053
00054 The available fields are:
00055 data
00056
00057 :param args: complete set of field values, in .msg order
00058 :param kwds: use keyword arguments corresponding to message field names
00059 to set specific fields.
00060 """
00061 if args or kwds:
00062 super(PR2GripperEventDetectorFeedback, self).__init__(*args, **kwds)
00063
00064 if self.data is None:
00065 self.data = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorData()
00066 else:
00067 self.data = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorData()
00068
00069 def _get_types(self):
00070 """
00071 internal API method
00072 """
00073 return self._slot_types
00074
00075 def serialize(self, buff):
00076 """
00077 serialize message into buffer
00078 :param buff: buffer, ``StringIO``
00079 """
00080 try:
00081 _x = self
00082 buff.write(_struct_2I3B.pack(_x.data.stamp.secs, _x.data.stamp.nsecs, _x.data.trigger_conditions_met, _x.data.slip_event, _x.data.acceleration_event))
00083 buff.write(_struct_3d.pack(*self.data.acceleration_vector))
00084 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00085 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00086
00087 def deserialize(self, str):
00088 """
00089 unpack serialized message in str into this message instance
00090 :param str: byte array of serialized message, ``str``
00091 """
00092 try:
00093 if self.data is None:
00094 self.data = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorData()
00095 end = 0
00096 _x = self
00097 start = end
00098 end += 11
00099 (_x.data.stamp.secs, _x.data.stamp.nsecs, _x.data.trigger_conditions_met, _x.data.slip_event, _x.data.acceleration_event,) = _struct_2I3B.unpack(str[start:end])
00100 self.data.trigger_conditions_met = bool(self.data.trigger_conditions_met)
00101 self.data.slip_event = bool(self.data.slip_event)
00102 self.data.acceleration_event = bool(self.data.acceleration_event)
00103 start = end
00104 end += 24
00105 self.data.acceleration_vector = _struct_3d.unpack(str[start:end])
00106 return self
00107 except struct.error as e:
00108 raise genpy.DeserializationError(e)
00109
00110
00111 def serialize_numpy(self, buff, numpy):
00112 """
00113 serialize message with numpy array types into buffer
00114 :param buff: buffer, ``StringIO``
00115 :param numpy: numpy python module
00116 """
00117 try:
00118 _x = self
00119 buff.write(_struct_2I3B.pack(_x.data.stamp.secs, _x.data.stamp.nsecs, _x.data.trigger_conditions_met, _x.data.slip_event, _x.data.acceleration_event))
00120 buff.write(self.data.acceleration_vector.tostring())
00121 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00122 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00123
00124 def deserialize_numpy(self, str, numpy):
00125 """
00126 unpack serialized message in str into this message instance using numpy for array types
00127 :param str: byte array of serialized message, ``str``
00128 :param numpy: numpy python module
00129 """
00130 try:
00131 if self.data is None:
00132 self.data = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorData()
00133 end = 0
00134 _x = self
00135 start = end
00136 end += 11
00137 (_x.data.stamp.secs, _x.data.stamp.nsecs, _x.data.trigger_conditions_met, _x.data.slip_event, _x.data.acceleration_event,) = _struct_2I3B.unpack(str[start:end])
00138 self.data.trigger_conditions_met = bool(self.data.trigger_conditions_met)
00139 self.data.slip_event = bool(self.data.slip_event)
00140 self.data.acceleration_event = bool(self.data.acceleration_event)
00141 start = end
00142 end += 24
00143 self.data.acceleration_vector = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=3)
00144 return self
00145 except struct.error as e:
00146 raise genpy.DeserializationError(e)
00147
00148 _struct_I = genpy.struct_I
00149 _struct_2I3B = struct.Struct("<2I3B")
00150 _struct_3d = struct.Struct("<3d")