Go to the documentation of this file.00001 """autogenerated by genpy from pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007
00008 class PR2GripperEventDetectorCommand(genpy.Message):
00009 _md5sum = "b91a7e1e863671a84c1d06e0cac3146e"
00010 _type = "pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand"
00011 _has_header = False
00012 _full_text = """# state variable that defines what events we would like to trigger on
00013 # Leaving this field blank will result in the robot triggering when
00014 # anything touches the sides of the finger or an impact is detected
00015 # with the hand/arm.
00016 int8 trigger_conditions
00017 # definitions for our various trigger_conditions values
00018 # trigger on either acceleration contact or finger sensor side impact
00019 int8 FINGER_SIDE_IMPACT_OR_ACC = 0
00020 # tigger once both slip and acceleration signals occur
00021 int8 SLIP_AND_ACC = 1
00022 # trigger on either slip, acceleration, or finger sensor side impact
00023 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2
00024 # trigger only on slip information
00025 int8 SLIP = 3
00026 # trigger only on acceleration contact information
00027 int8 ACC = 4
00028
00029
00030 # the amount of acceleration to trigger on (acceleration vector magnitude)
00031 # Units = m/s^2
00032 # The user needs to be concerned here about not setting the trigger too
00033 # low so that is set off by the robot's own motions.
00034 #
00035 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level
00036 # For small delicate controlled motions this can be set MUCH lower (try 2.0)
00037 #
00038 # NOTE: When moving the gripper joint (opening/closing the grippr)
00039 # the high gearing of the PR2 gripper causes large acceleration vibrations
00040 # which will cause triggering to occur. This is a known drawback of the PR2.
00041 #
00042 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you
00043 # are using a trigger_conditions value that returns on acceleration contact
00044 # events then it will immediately exceed your trigger and return
00045 float64 acceleration_trigger_magnitude
00046
00047
00048 # the slip detector gain to trigger on (either finger) : try 0.01
00049 # higher values decrease slip sensitivty (to a point)
00050 # lower values increase sensitivity (to a point)
00051 #
00052 # NOTE: Leaving this value blank will result in the most sensitive slip level.
00053 float64 slip_trigger_magnitude
00054 """
00055
00056 FINGER_SIDE_IMPACT_OR_ACC = 0
00057 SLIP_AND_ACC = 1
00058 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2
00059 SLIP = 3
00060 ACC = 4
00061
00062 __slots__ = ['trigger_conditions','acceleration_trigger_magnitude','slip_trigger_magnitude']
00063 _slot_types = ['int8','float64','float64']
00064
00065 def __init__(self, *args, **kwds):
00066 """
00067 Constructor. Any message fields that are implicitly/explicitly
00068 set to None will be assigned a default value. The recommend
00069 use is keyword arguments as this is more robust to future message
00070 changes. You cannot mix in-order arguments and keyword arguments.
00071
00072 The available fields are:
00073 trigger_conditions,acceleration_trigger_magnitude,slip_trigger_magnitude
00074
00075 :param args: complete set of field values, in .msg order
00076 :param kwds: use keyword arguments corresponding to message field names
00077 to set specific fields.
00078 """
00079 if args or kwds:
00080 super(PR2GripperEventDetectorCommand, self).__init__(*args, **kwds)
00081
00082 if self.trigger_conditions is None:
00083 self.trigger_conditions = 0
00084 if self.acceleration_trigger_magnitude is None:
00085 self.acceleration_trigger_magnitude = 0.
00086 if self.slip_trigger_magnitude is None:
00087 self.slip_trigger_magnitude = 0.
00088 else:
00089 self.trigger_conditions = 0
00090 self.acceleration_trigger_magnitude = 0.
00091 self.slip_trigger_magnitude = 0.
00092
00093 def _get_types(self):
00094 """
00095 internal API method
00096 """
00097 return self._slot_types
00098
00099 def serialize(self, buff):
00100 """
00101 serialize message into buffer
00102 :param buff: buffer, ``StringIO``
00103 """
00104 try:
00105 _x = self
00106 buff.write(_struct_b2d.pack(_x.trigger_conditions, _x.acceleration_trigger_magnitude, _x.slip_trigger_magnitude))
00107 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00108 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00109
00110 def deserialize(self, str):
00111 """
00112 unpack serialized message in str into this message instance
00113 :param str: byte array of serialized message, ``str``
00114 """
00115 try:
00116 end = 0
00117 _x = self
00118 start = end
00119 end += 17
00120 (_x.trigger_conditions, _x.acceleration_trigger_magnitude, _x.slip_trigger_magnitude,) = _struct_b2d.unpack(str[start:end])
00121 return self
00122 except struct.error as e:
00123 raise genpy.DeserializationError(e)
00124
00125
00126 def serialize_numpy(self, buff, numpy):
00127 """
00128 serialize message with numpy array types into buffer
00129 :param buff: buffer, ``StringIO``
00130 :param numpy: numpy python module
00131 """
00132 try:
00133 _x = self
00134 buff.write(_struct_b2d.pack(_x.trigger_conditions, _x.acceleration_trigger_magnitude, _x.slip_trigger_magnitude))
00135 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00136 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00137
00138 def deserialize_numpy(self, str, numpy):
00139 """
00140 unpack serialized message in str into this message instance using numpy for array types
00141 :param str: byte array of serialized message, ``str``
00142 :param numpy: numpy python module
00143 """
00144 try:
00145 end = 0
00146 _x = self
00147 start = end
00148 end += 17
00149 (_x.trigger_conditions, _x.acceleration_trigger_magnitude, _x.slip_trigger_magnitude,) = _struct_b2d.unpack(str[start:end])
00150 return self
00151 except struct.error as e:
00152 raise genpy.DeserializationError(e)
00153
00154 _struct_I = genpy.struct_I
00155 _struct_b2d = struct.Struct("<b2d")