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