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