$search
00001 """autogenerated by genmsg_py from PR2GripperReleaseActionGoal.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import roslib.rostime 00006 import actionlib_msgs.msg 00007 import pr2_gripper_sensor_msgs.msg 00008 import std_msgs.msg 00009 00010 class PR2GripperReleaseActionGoal(roslib.message.Message): 00011 _md5sum = "e5f06f3717f8990527330a2e0eaa0c81" 00012 _type = "pr2_gripper_sensor_msgs/PR2GripperReleaseActionGoal" 00013 _has_header = True #flag to mark the presence of a Header object 00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00015 00016 Header header 00017 actionlib_msgs/GoalID goal_id 00018 PR2GripperReleaseGoal goal 00019 00020 ================================================================================ 00021 MSG: std_msgs/Header 00022 # Standard metadata for higher-level stamped data types. 00023 # This is generally used to communicate timestamped data 00024 # in a particular coordinate frame. 00025 # 00026 # sequence ID: consecutively increasing ID 00027 uint32 seq 00028 #Two-integer timestamp that is expressed as: 00029 # * stamp.secs: seconds (stamp_secs) since epoch 00030 # * stamp.nsecs: nanoseconds since stamp_secs 00031 # time-handling sugar is provided by the client library 00032 time stamp 00033 #Frame this data is associated with 00034 # 0: no frame 00035 # 1: global frame 00036 string frame_id 00037 00038 ================================================================================ 00039 MSG: actionlib_msgs/GoalID 00040 # The stamp should store the time at which this goal was requested. 00041 # It is used by an action server when it tries to preempt all 00042 # goals that were requested before a certain time 00043 time stamp 00044 00045 # The id provides a way to associate feedback and 00046 # result message with specific goal requests. The id 00047 # specified must be unique. 00048 string id 00049 00050 00051 ================================================================================ 00052 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseGoal 00053 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00054 #goal 00055 PR2GripperReleaseCommand command 00056 00057 ================================================================================ 00058 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseCommand 00059 # the event conditions we would like to trigger the robot to release on 00060 PR2GripperEventDetectorCommand event 00061 ================================================================================ 00062 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand 00063 # state variable that defines what events we would like to trigger on 00064 # Leaving this field blank will result in the robot triggering when 00065 # anything touches the sides of the finger or an impact is detected 00066 # with the hand/arm. 00067 int8 trigger_conditions 00068 # definitions for our various trigger_conditions values 00069 # trigger on either acceleration contact or finger sensor side impact 00070 int8 FINGER_SIDE_IMPACT_OR_ACC = 0 00071 # tigger once both slip and acceleration signals occur 00072 int8 SLIP_AND_ACC = 1 00073 # trigger on either slip, acceleration, or finger sensor side impact 00074 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2 00075 # trigger only on slip information 00076 int8 SLIP = 3 00077 # trigger only on acceleration contact information 00078 int8 ACC = 4 00079 00080 00081 # the amount of acceleration to trigger on (acceleration vector magnitude) 00082 # Units = m/s^2 00083 # The user needs to be concerned here about not setting the trigger too 00084 # low so that is set off by the robot's own motions. 00085 # 00086 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level 00087 # For small delicate controlled motions this can be set MUCH lower (try 2.0) 00088 # 00089 # NOTE: When moving the gripper joint (opening/closing the grippr) 00090 # the high gearing of the PR2 gripper causes large acceleration vibrations 00091 # which will cause triggering to occur. This is a known drawback of the PR2. 00092 # 00093 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you 00094 # are using a trigger_conditions value that returns on acceleration contact 00095 # events then it will immediately exceed your trigger and return 00096 float64 acceleration_trigger_magnitude 00097 00098 00099 # the slip detector gain to trigger on (either finger) : try 0.01 00100 # higher values decrease slip sensitivty (to a point) 00101 # lower values increase sensitivity (to a point) 00102 # 00103 # NOTE: Leaving this value blank will result in the most sensitive slip level. 00104 float64 slip_trigger_magnitude 00105 """ 00106 __slots__ = ['header','goal_id','goal'] 00107 _slot_types = ['Header','actionlib_msgs/GoalID','pr2_gripper_sensor_msgs/PR2GripperReleaseGoal'] 00108 00109 def __init__(self, *args, **kwds): 00110 """ 00111 Constructor. Any message fields that are implicitly/explicitly 00112 set to None will be assigned a default value. The recommend 00113 use is keyword arguments as this is more robust to future message 00114 changes. You cannot mix in-order arguments and keyword arguments. 00115 00116 The available fields are: 00117 header,goal_id,goal 00118 00119 @param args: complete set of field values, in .msg order 00120 @param kwds: use keyword arguments corresponding to message field names 00121 to set specific fields. 00122 """ 00123 if args or kwds: 00124 super(PR2GripperReleaseActionGoal, self).__init__(*args, **kwds) 00125 #message fields cannot be None, assign default values for those that are 00126 if self.header is None: 00127 self.header = std_msgs.msg._Header.Header() 00128 if self.goal_id is None: 00129 self.goal_id = actionlib_msgs.msg.GoalID() 00130 if self.goal is None: 00131 self.goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseGoal() 00132 else: 00133 self.header = std_msgs.msg._Header.Header() 00134 self.goal_id = actionlib_msgs.msg.GoalID() 00135 self.goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseGoal() 00136 00137 def _get_types(self): 00138 """ 00139 internal API method 00140 """ 00141 return self._slot_types 00142 00143 def serialize(self, buff): 00144 """ 00145 serialize message into buffer 00146 @param buff: buffer 00147 @type buff: StringIO 00148 """ 00149 try: 00150 _x = self 00151 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00152 _x = self.header.frame_id 00153 length = len(_x) 00154 buff.write(struct.pack('<I%ss'%length, length, _x)) 00155 _x = self 00156 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs)) 00157 _x = self.goal_id.id 00158 length = len(_x) 00159 buff.write(struct.pack('<I%ss'%length, length, _x)) 00160 _x = self 00161 buff.write(_struct_b2d.pack(_x.goal.command.event.trigger_conditions, _x.goal.command.event.acceleration_trigger_magnitude, _x.goal.command.event.slip_trigger_magnitude)) 00162 except struct.error as se: self._check_types(se) 00163 except TypeError as te: self._check_types(te) 00164 00165 def deserialize(self, str): 00166 """ 00167 unpack serialized message in str into this message instance 00168 @param str: byte array of serialized message 00169 @type str: str 00170 """ 00171 try: 00172 if self.header is None: 00173 self.header = std_msgs.msg._Header.Header() 00174 if self.goal_id is None: 00175 self.goal_id = actionlib_msgs.msg.GoalID() 00176 if self.goal is None: 00177 self.goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseGoal() 00178 end = 0 00179 _x = self 00180 start = end 00181 end += 12 00182 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00183 start = end 00184 end += 4 00185 (length,) = _struct_I.unpack(str[start:end]) 00186 start = end 00187 end += length 00188 self.header.frame_id = str[start:end] 00189 _x = self 00190 start = end 00191 end += 8 00192 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00193 start = end 00194 end += 4 00195 (length,) = _struct_I.unpack(str[start:end]) 00196 start = end 00197 end += length 00198 self.goal_id.id = str[start:end] 00199 _x = self 00200 start = end 00201 end += 17 00202 (_x.goal.command.event.trigger_conditions, _x.goal.command.event.acceleration_trigger_magnitude, _x.goal.command.event.slip_trigger_magnitude,) = _struct_b2d.unpack(str[start:end]) 00203 return self 00204 except struct.error as e: 00205 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00206 00207 00208 def serialize_numpy(self, buff, numpy): 00209 """ 00210 serialize message with numpy array types into buffer 00211 @param buff: buffer 00212 @type buff: StringIO 00213 @param numpy: numpy python module 00214 @type numpy module 00215 """ 00216 try: 00217 _x = self 00218 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00219 _x = self.header.frame_id 00220 length = len(_x) 00221 buff.write(struct.pack('<I%ss'%length, length, _x)) 00222 _x = self 00223 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs)) 00224 _x = self.goal_id.id 00225 length = len(_x) 00226 buff.write(struct.pack('<I%ss'%length, length, _x)) 00227 _x = self 00228 buff.write(_struct_b2d.pack(_x.goal.command.event.trigger_conditions, _x.goal.command.event.acceleration_trigger_magnitude, _x.goal.command.event.slip_trigger_magnitude)) 00229 except struct.error as se: self._check_types(se) 00230 except TypeError as te: self._check_types(te) 00231 00232 def deserialize_numpy(self, str, numpy): 00233 """ 00234 unpack serialized message in str into this message instance using numpy for array types 00235 @param str: byte array of serialized message 00236 @type str: str 00237 @param numpy: numpy python module 00238 @type numpy: module 00239 """ 00240 try: 00241 if self.header is None: 00242 self.header = std_msgs.msg._Header.Header() 00243 if self.goal_id is None: 00244 self.goal_id = actionlib_msgs.msg.GoalID() 00245 if self.goal is None: 00246 self.goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseGoal() 00247 end = 0 00248 _x = self 00249 start = end 00250 end += 12 00251 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00252 start = end 00253 end += 4 00254 (length,) = _struct_I.unpack(str[start:end]) 00255 start = end 00256 end += length 00257 self.header.frame_id = str[start:end] 00258 _x = self 00259 start = end 00260 end += 8 00261 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00262 start = end 00263 end += 4 00264 (length,) = _struct_I.unpack(str[start:end]) 00265 start = end 00266 end += length 00267 self.goal_id.id = str[start:end] 00268 _x = self 00269 start = end 00270 end += 17 00271 (_x.goal.command.event.trigger_conditions, _x.goal.command.event.acceleration_trigger_magnitude, _x.goal.command.event.slip_trigger_magnitude,) = _struct_b2d.unpack(str[start:end]) 00272 return self 00273 except struct.error as e: 00274 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00275 00276 _struct_I = roslib.message.struct_I 00277 _struct_3I = struct.Struct("<3I") 00278 _struct_b2d = struct.Struct("<b2d") 00279 _struct_2I = struct.Struct("<2I")