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