$search
00001 """autogenerated by genmsg_py from PR2GripperFindContactActionFeedback.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 PR2GripperFindContactActionFeedback(roslib.message.Message): 00011 _md5sum = "6f5508091ee61f963690fb74fc7df932" 00012 _type = "pr2_gripper_sensor_msgs/PR2GripperFindContactActionFeedback" 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/GoalStatus status 00018 PR2GripperFindContactFeedback feedback 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/GoalStatus 00040 GoalID goal_id 00041 uint8 status 00042 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00043 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00044 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00045 # and has since completed its execution (Terminal State) 00046 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00047 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00048 # to some failure (Terminal State) 00049 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00050 # because the goal was unattainable or invalid (Terminal State) 00051 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00052 # and has not yet completed execution 00053 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00054 # but the action server has not yet confirmed that the goal is canceled 00055 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00056 # and was successfully cancelled (Terminal State) 00057 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00058 # sent over the wire by an action server 00059 00060 #Allow for the user to associate a string with GoalStatus for debugging 00061 string text 00062 00063 00064 ================================================================================ 00065 MSG: actionlib_msgs/GoalID 00066 # The stamp should store the time at which this goal was requested. 00067 # It is used by an action server when it tries to preempt all 00068 # goals that were requested before a certain time 00069 time stamp 00070 00071 # The id provides a way to associate feedback and 00072 # result message with specific goal requests. The id 00073 # specified must be unique. 00074 string id 00075 00076 00077 ================================================================================ 00078 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactFeedback 00079 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00080 # feedback 00081 PR2GripperFindContactData data 00082 00083 00084 00085 ================================================================================ 00086 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactData 00087 # Time the data was recorded at 00088 time stamp 00089 00090 # true when our contact conditions have been met 00091 # (see PR2GripperFindContact command) 00092 bool contact_conditions_met 00093 00094 # the finger contact conditions 00095 # true if the finger experienced a contact event 00096 # 00097 # contact events are defined as contact with the fingerpads 00098 # as either steady-state or high-freq force events 00099 bool left_fingertip_pad_contact 00100 bool right_fingertip_pad_contact 00101 00102 # the force experinced by the finger Pads (N) 00103 # NOTE:this ignores data from the edges of the finger pressure 00104 float64 left_fingertip_pad_force 00105 float64 right_fingertip_pad_force 00106 00107 # the current joint position (m) 00108 float64 joint_position 00109 00110 # the virtual (parallel) joint effort (N) 00111 float64 joint_effort 00112 00113 # the control state of our realtime controller 00114 PR2GripperSensorRTState rtstate 00115 ================================================================================ 00116 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState 00117 # the control state of our realtime controller 00118 int8 realtime_controller_state 00119 00120 # predefined values to indicate our realtime_controller_state 00121 int8 DISABLED = 0 00122 int8 POSITION_SERVO = 3 00123 int8 FORCE_SERVO = 4 00124 int8 FIND_CONTACT = 5 00125 int8 SLIP_SERVO = 6 00126 """ 00127 __slots__ = ['header','status','feedback'] 00128 _slot_types = ['Header','actionlib_msgs/GoalStatus','pr2_gripper_sensor_msgs/PR2GripperFindContactFeedback'] 00129 00130 def __init__(self, *args, **kwds): 00131 """ 00132 Constructor. Any message fields that are implicitly/explicitly 00133 set to None will be assigned a default value. The recommend 00134 use is keyword arguments as this is more robust to future message 00135 changes. You cannot mix in-order arguments and keyword arguments. 00136 00137 The available fields are: 00138 header,status,feedback 00139 00140 @param args: complete set of field values, in .msg order 00141 @param kwds: use keyword arguments corresponding to message field names 00142 to set specific fields. 00143 """ 00144 if args or kwds: 00145 super(PR2GripperFindContactActionFeedback, self).__init__(*args, **kwds) 00146 #message fields cannot be None, assign default values for those that are 00147 if self.header is None: 00148 self.header = std_msgs.msg._Header.Header() 00149 if self.status is None: 00150 self.status = actionlib_msgs.msg.GoalStatus() 00151 if self.feedback is None: 00152 self.feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactFeedback() 00153 else: 00154 self.header = std_msgs.msg._Header.Header() 00155 self.status = actionlib_msgs.msg.GoalStatus() 00156 self.feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactFeedback() 00157 00158 def _get_types(self): 00159 """ 00160 internal API method 00161 """ 00162 return self._slot_types 00163 00164 def serialize(self, buff): 00165 """ 00166 serialize message into buffer 00167 @param buff: buffer 00168 @type buff: StringIO 00169 """ 00170 try: 00171 _x = self 00172 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00173 _x = self.header.frame_id 00174 length = len(_x) 00175 buff.write(struct.pack('<I%ss'%length, length, _x)) 00176 _x = self 00177 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00178 _x = self.status.goal_id.id 00179 length = len(_x) 00180 buff.write(struct.pack('<I%ss'%length, length, _x)) 00181 buff.write(_struct_B.pack(self.status.status)) 00182 _x = self.status.text 00183 length = len(_x) 00184 buff.write(struct.pack('<I%ss'%length, length, _x)) 00185 _x = self 00186 buff.write(_struct_2I3B4db.pack(_x.feedback.data.stamp.secs, _x.feedback.data.stamp.nsecs, _x.feedback.data.contact_conditions_met, _x.feedback.data.left_fingertip_pad_contact, _x.feedback.data.right_fingertip_pad_contact, _x.feedback.data.left_fingertip_pad_force, _x.feedback.data.right_fingertip_pad_force, _x.feedback.data.joint_position, _x.feedback.data.joint_effort, _x.feedback.data.rtstate.realtime_controller_state)) 00187 except struct.error as se: self._check_types(se) 00188 except TypeError as te: self._check_types(te) 00189 00190 def deserialize(self, str): 00191 """ 00192 unpack serialized message in str into this message instance 00193 @param str: byte array of serialized message 00194 @type str: str 00195 """ 00196 try: 00197 if self.header is None: 00198 self.header = std_msgs.msg._Header.Header() 00199 if self.status is None: 00200 self.status = actionlib_msgs.msg.GoalStatus() 00201 if self.feedback is None: 00202 self.feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactFeedback() 00203 end = 0 00204 _x = self 00205 start = end 00206 end += 12 00207 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00208 start = end 00209 end += 4 00210 (length,) = _struct_I.unpack(str[start:end]) 00211 start = end 00212 end += length 00213 self.header.frame_id = str[start:end] 00214 _x = self 00215 start = end 00216 end += 8 00217 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00218 start = end 00219 end += 4 00220 (length,) = _struct_I.unpack(str[start:end]) 00221 start = end 00222 end += length 00223 self.status.goal_id.id = str[start:end] 00224 start = end 00225 end += 1 00226 (self.status.status,) = _struct_B.unpack(str[start:end]) 00227 start = end 00228 end += 4 00229 (length,) = _struct_I.unpack(str[start:end]) 00230 start = end 00231 end += length 00232 self.status.text = str[start:end] 00233 _x = self 00234 start = end 00235 end += 44 00236 (_x.feedback.data.stamp.secs, _x.feedback.data.stamp.nsecs, _x.feedback.data.contact_conditions_met, _x.feedback.data.left_fingertip_pad_contact, _x.feedback.data.right_fingertip_pad_contact, _x.feedback.data.left_fingertip_pad_force, _x.feedback.data.right_fingertip_pad_force, _x.feedback.data.joint_position, _x.feedback.data.joint_effort, _x.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3B4db.unpack(str[start:end]) 00237 self.feedback.data.contact_conditions_met = bool(self.feedback.data.contact_conditions_met) 00238 self.feedback.data.left_fingertip_pad_contact = bool(self.feedback.data.left_fingertip_pad_contact) 00239 self.feedback.data.right_fingertip_pad_contact = bool(self.feedback.data.right_fingertip_pad_contact) 00240 return self 00241 except struct.error as e: 00242 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00243 00244 00245 def serialize_numpy(self, buff, numpy): 00246 """ 00247 serialize message with numpy array types into buffer 00248 @param buff: buffer 00249 @type buff: StringIO 00250 @param numpy: numpy python module 00251 @type numpy module 00252 """ 00253 try: 00254 _x = self 00255 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00256 _x = self.header.frame_id 00257 length = len(_x) 00258 buff.write(struct.pack('<I%ss'%length, length, _x)) 00259 _x = self 00260 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs)) 00261 _x = self.status.goal_id.id 00262 length = len(_x) 00263 buff.write(struct.pack('<I%ss'%length, length, _x)) 00264 buff.write(_struct_B.pack(self.status.status)) 00265 _x = self.status.text 00266 length = len(_x) 00267 buff.write(struct.pack('<I%ss'%length, length, _x)) 00268 _x = self 00269 buff.write(_struct_2I3B4db.pack(_x.feedback.data.stamp.secs, _x.feedback.data.stamp.nsecs, _x.feedback.data.contact_conditions_met, _x.feedback.data.left_fingertip_pad_contact, _x.feedback.data.right_fingertip_pad_contact, _x.feedback.data.left_fingertip_pad_force, _x.feedback.data.right_fingertip_pad_force, _x.feedback.data.joint_position, _x.feedback.data.joint_effort, _x.feedback.data.rtstate.realtime_controller_state)) 00270 except struct.error as se: self._check_types(se) 00271 except TypeError as te: self._check_types(te) 00272 00273 def deserialize_numpy(self, str, numpy): 00274 """ 00275 unpack serialized message in str into this message instance using numpy for array types 00276 @param str: byte array of serialized message 00277 @type str: str 00278 @param numpy: numpy python module 00279 @type numpy: module 00280 """ 00281 try: 00282 if self.header is None: 00283 self.header = std_msgs.msg._Header.Header() 00284 if self.status is None: 00285 self.status = actionlib_msgs.msg.GoalStatus() 00286 if self.feedback is None: 00287 self.feedback = pr2_gripper_sensor_msgs.msg.PR2GripperFindContactFeedback() 00288 end = 0 00289 _x = self 00290 start = end 00291 end += 12 00292 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00293 start = end 00294 end += 4 00295 (length,) = _struct_I.unpack(str[start:end]) 00296 start = end 00297 end += length 00298 self.header.frame_id = str[start:end] 00299 _x = self 00300 start = end 00301 end += 8 00302 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00303 start = end 00304 end += 4 00305 (length,) = _struct_I.unpack(str[start:end]) 00306 start = end 00307 end += length 00308 self.status.goal_id.id = str[start:end] 00309 start = end 00310 end += 1 00311 (self.status.status,) = _struct_B.unpack(str[start:end]) 00312 start = end 00313 end += 4 00314 (length,) = _struct_I.unpack(str[start:end]) 00315 start = end 00316 end += length 00317 self.status.text = str[start:end] 00318 _x = self 00319 start = end 00320 end += 44 00321 (_x.feedback.data.stamp.secs, _x.feedback.data.stamp.nsecs, _x.feedback.data.contact_conditions_met, _x.feedback.data.left_fingertip_pad_contact, _x.feedback.data.right_fingertip_pad_contact, _x.feedback.data.left_fingertip_pad_force, _x.feedback.data.right_fingertip_pad_force, _x.feedback.data.joint_position, _x.feedback.data.joint_effort, _x.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3B4db.unpack(str[start:end]) 00322 self.feedback.data.contact_conditions_met = bool(self.feedback.data.contact_conditions_met) 00323 self.feedback.data.left_fingertip_pad_contact = bool(self.feedback.data.left_fingertip_pad_contact) 00324 self.feedback.data.right_fingertip_pad_contact = bool(self.feedback.data.right_fingertip_pad_contact) 00325 return self 00326 except struct.error as e: 00327 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00328 00329 _struct_I = roslib.message.struct_I 00330 _struct_3I = struct.Struct("<3I") 00331 _struct_B = struct.Struct("<B") 00332 _struct_2I = struct.Struct("<2I") 00333 _struct_2I3B4db = struct.Struct("<2I3B4db")