$search
00001 """autogenerated by genmsg_py from PR2GripperGrabAction.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 PR2GripperGrabAction(roslib.message.Message): 00011 _md5sum = "f467562414aabe5b90666be976b0c379" 00012 _type = "pr2_gripper_sensor_msgs/PR2GripperGrabAction" 00013 _has_header = False #flag to mark the presence of a Header object 00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00015 00016 PR2GripperGrabActionGoal action_goal 00017 PR2GripperGrabActionResult action_result 00018 PR2GripperGrabActionFeedback action_feedback 00019 00020 ================================================================================ 00021 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabActionGoal 00022 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00023 00024 Header header 00025 actionlib_msgs/GoalID goal_id 00026 PR2GripperGrabGoal goal 00027 00028 ================================================================================ 00029 MSG: std_msgs/Header 00030 # Standard metadata for higher-level stamped data types. 00031 # This is generally used to communicate timestamped data 00032 # in a particular coordinate frame. 00033 # 00034 # sequence ID: consecutively increasing ID 00035 uint32 seq 00036 #Two-integer timestamp that is expressed as: 00037 # * stamp.secs: seconds (stamp_secs) since epoch 00038 # * stamp.nsecs: nanoseconds since stamp_secs 00039 # time-handling sugar is provided by the client library 00040 time stamp 00041 #Frame this data is associated with 00042 # 0: no frame 00043 # 1: global frame 00044 string frame_id 00045 00046 ================================================================================ 00047 MSG: actionlib_msgs/GoalID 00048 # The stamp should store the time at which this goal was requested. 00049 # It is used by an action server when it tries to preempt all 00050 # goals that were requested before a certain time 00051 time stamp 00052 00053 # The id provides a way to associate feedback and 00054 # result message with specific goal requests. The id 00055 # specified must be unique. 00056 string id 00057 00058 00059 ================================================================================ 00060 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabGoal 00061 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00062 #goal 00063 PR2GripperGrabCommand command 00064 00065 ================================================================================ 00066 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabCommand 00067 # The gain to use to evaluate how hard an object should be 00068 # grasped after it is contacted. This is based on hardness 00069 # estimation as outlined in TRO paper (see wiki). 00070 # 00071 # Try 0.03 00072 # 00073 # Units (N/(m/s^2)) 00074 float64 hardness_gain 00075 00076 ================================================================================ 00077 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabActionResult 00078 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00079 00080 Header header 00081 actionlib_msgs/GoalStatus status 00082 PR2GripperGrabResult result 00083 00084 ================================================================================ 00085 MSG: actionlib_msgs/GoalStatus 00086 GoalID goal_id 00087 uint8 status 00088 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00089 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00090 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00091 # and has since completed its execution (Terminal State) 00092 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00093 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00094 # to some failure (Terminal State) 00095 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00096 # because the goal was unattainable or invalid (Terminal State) 00097 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00098 # and has not yet completed execution 00099 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00100 # but the action server has not yet confirmed that the goal is canceled 00101 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00102 # and was successfully cancelled (Terminal State) 00103 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00104 # sent over the wire by an action server 00105 00106 #Allow for the user to associate a string with GoalStatus for debugging 00107 string text 00108 00109 00110 ================================================================================ 00111 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabResult 00112 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00113 #result 00114 PR2GripperGrabData data 00115 00116 ================================================================================ 00117 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabData 00118 # the control state of our realtime controller 00119 PR2GripperSensorRTState rtstate 00120 ================================================================================ 00121 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState 00122 # the control state of our realtime controller 00123 int8 realtime_controller_state 00124 00125 # predefined values to indicate our realtime_controller_state 00126 int8 DISABLED = 0 00127 int8 POSITION_SERVO = 3 00128 int8 FORCE_SERVO = 4 00129 int8 FIND_CONTACT = 5 00130 int8 SLIP_SERVO = 6 00131 ================================================================================ 00132 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabActionFeedback 00133 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00134 00135 Header header 00136 actionlib_msgs/GoalStatus status 00137 PR2GripperGrabFeedback feedback 00138 00139 ================================================================================ 00140 MSG: pr2_gripper_sensor_msgs/PR2GripperGrabFeedback 00141 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00142 00143 #feedback 00144 PR2GripperGrabData data 00145 00146 00147 """ 00148 __slots__ = ['action_goal','action_result','action_feedback'] 00149 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperGrabActionGoal','pr2_gripper_sensor_msgs/PR2GripperGrabActionResult','pr2_gripper_sensor_msgs/PR2GripperGrabActionFeedback'] 00150 00151 def __init__(self, *args, **kwds): 00152 """ 00153 Constructor. Any message fields that are implicitly/explicitly 00154 set to None will be assigned a default value. The recommend 00155 use is keyword arguments as this is more robust to future message 00156 changes. You cannot mix in-order arguments and keyword arguments. 00157 00158 The available fields are: 00159 action_goal,action_result,action_feedback 00160 00161 @param args: complete set of field values, in .msg order 00162 @param kwds: use keyword arguments corresponding to message field names 00163 to set specific fields. 00164 """ 00165 if args or kwds: 00166 super(PR2GripperGrabAction, self).__init__(*args, **kwds) 00167 #message fields cannot be None, assign default values for those that are 00168 if self.action_goal is None: 00169 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionGoal() 00170 if self.action_result is None: 00171 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionResult() 00172 if self.action_feedback is None: 00173 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionFeedback() 00174 else: 00175 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionGoal() 00176 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionResult() 00177 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionFeedback() 00178 00179 def _get_types(self): 00180 """ 00181 internal API method 00182 """ 00183 return self._slot_types 00184 00185 def serialize(self, buff): 00186 """ 00187 serialize message into buffer 00188 @param buff: buffer 00189 @type buff: StringIO 00190 """ 00191 try: 00192 _x = self 00193 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00194 _x = self.action_goal.header.frame_id 00195 length = len(_x) 00196 buff.write(struct.pack('<I%ss'%length, length, _x)) 00197 _x = self 00198 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00199 _x = self.action_goal.goal_id.id 00200 length = len(_x) 00201 buff.write(struct.pack('<I%ss'%length, length, _x)) 00202 _x = self 00203 buff.write(_struct_d3I.pack(_x.action_goal.goal.command.hardness_gain, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00204 _x = self.action_result.header.frame_id 00205 length = len(_x) 00206 buff.write(struct.pack('<I%ss'%length, length, _x)) 00207 _x = self 00208 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00209 _x = self.action_result.status.goal_id.id 00210 length = len(_x) 00211 buff.write(struct.pack('<I%ss'%length, length, _x)) 00212 buff.write(_struct_B.pack(self.action_result.status.status)) 00213 _x = self.action_result.status.text 00214 length = len(_x) 00215 buff.write(struct.pack('<I%ss'%length, length, _x)) 00216 _x = self 00217 buff.write(_struct_b3I.pack(_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00218 _x = self.action_feedback.header.frame_id 00219 length = len(_x) 00220 buff.write(struct.pack('<I%ss'%length, length, _x)) 00221 _x = self 00222 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00223 _x = self.action_feedback.status.goal_id.id 00224 length = len(_x) 00225 buff.write(struct.pack('<I%ss'%length, length, _x)) 00226 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00227 _x = self.action_feedback.status.text 00228 length = len(_x) 00229 buff.write(struct.pack('<I%ss'%length, length, _x)) 00230 buff.write(_struct_b.pack(self.action_feedback.feedback.data.rtstate.realtime_controller_state)) 00231 except struct.error as se: self._check_types(se) 00232 except TypeError as te: self._check_types(te) 00233 00234 def deserialize(self, str): 00235 """ 00236 unpack serialized message in str into this message instance 00237 @param str: byte array of serialized message 00238 @type str: str 00239 """ 00240 try: 00241 if self.action_goal is None: 00242 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionGoal() 00243 if self.action_result is None: 00244 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionResult() 00245 if self.action_feedback is None: 00246 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionFeedback() 00247 end = 0 00248 _x = self 00249 start = end 00250 end += 12 00251 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.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.action_goal.header.frame_id = str[start:end] 00258 _x = self 00259 start = end 00260 end += 8 00261 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.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.action_goal.goal_id.id = str[start:end] 00268 _x = self 00269 start = end 00270 end += 20 00271 (_x.action_goal.goal.command.hardness_gain, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end]) 00272 start = end 00273 end += 4 00274 (length,) = _struct_I.unpack(str[start:end]) 00275 start = end 00276 end += length 00277 self.action_result.header.frame_id = str[start:end] 00278 _x = self 00279 start = end 00280 end += 8 00281 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00282 start = end 00283 end += 4 00284 (length,) = _struct_I.unpack(str[start:end]) 00285 start = end 00286 end += length 00287 self.action_result.status.goal_id.id = str[start:end] 00288 start = end 00289 end += 1 00290 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 00291 start = end 00292 end += 4 00293 (length,) = _struct_I.unpack(str[start:end]) 00294 start = end 00295 end += length 00296 self.action_result.status.text = str[start:end] 00297 _x = self 00298 start = end 00299 end += 13 00300 (_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end]) 00301 start = end 00302 end += 4 00303 (length,) = _struct_I.unpack(str[start:end]) 00304 start = end 00305 end += length 00306 self.action_feedback.header.frame_id = str[start:end] 00307 _x = self 00308 start = end 00309 end += 8 00310 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00311 start = end 00312 end += 4 00313 (length,) = _struct_I.unpack(str[start:end]) 00314 start = end 00315 end += length 00316 self.action_feedback.status.goal_id.id = str[start:end] 00317 start = end 00318 end += 1 00319 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00320 start = end 00321 end += 4 00322 (length,) = _struct_I.unpack(str[start:end]) 00323 start = end 00324 end += length 00325 self.action_feedback.status.text = str[start:end] 00326 start = end 00327 end += 1 00328 (self.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_b.unpack(str[start:end]) 00329 return self 00330 except struct.error as e: 00331 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00332 00333 00334 def serialize_numpy(self, buff, numpy): 00335 """ 00336 serialize message with numpy array types into buffer 00337 @param buff: buffer 00338 @type buff: StringIO 00339 @param numpy: numpy python module 00340 @type numpy module 00341 """ 00342 try: 00343 _x = self 00344 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00345 _x = self.action_goal.header.frame_id 00346 length = len(_x) 00347 buff.write(struct.pack('<I%ss'%length, length, _x)) 00348 _x = self 00349 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00350 _x = self.action_goal.goal_id.id 00351 length = len(_x) 00352 buff.write(struct.pack('<I%ss'%length, length, _x)) 00353 _x = self 00354 buff.write(_struct_d3I.pack(_x.action_goal.goal.command.hardness_gain, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00355 _x = self.action_result.header.frame_id 00356 length = len(_x) 00357 buff.write(struct.pack('<I%ss'%length, length, _x)) 00358 _x = self 00359 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00360 _x = self.action_result.status.goal_id.id 00361 length = len(_x) 00362 buff.write(struct.pack('<I%ss'%length, length, _x)) 00363 buff.write(_struct_B.pack(self.action_result.status.status)) 00364 _x = self.action_result.status.text 00365 length = len(_x) 00366 buff.write(struct.pack('<I%ss'%length, length, _x)) 00367 _x = self 00368 buff.write(_struct_b3I.pack(_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00369 _x = self.action_feedback.header.frame_id 00370 length = len(_x) 00371 buff.write(struct.pack('<I%ss'%length, length, _x)) 00372 _x = self 00373 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00374 _x = self.action_feedback.status.goal_id.id 00375 length = len(_x) 00376 buff.write(struct.pack('<I%ss'%length, length, _x)) 00377 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00378 _x = self.action_feedback.status.text 00379 length = len(_x) 00380 buff.write(struct.pack('<I%ss'%length, length, _x)) 00381 buff.write(_struct_b.pack(self.action_feedback.feedback.data.rtstate.realtime_controller_state)) 00382 except struct.error as se: self._check_types(se) 00383 except TypeError as te: self._check_types(te) 00384 00385 def deserialize_numpy(self, str, numpy): 00386 """ 00387 unpack serialized message in str into this message instance using numpy for array types 00388 @param str: byte array of serialized message 00389 @type str: str 00390 @param numpy: numpy python module 00391 @type numpy: module 00392 """ 00393 try: 00394 if self.action_goal is None: 00395 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionGoal() 00396 if self.action_result is None: 00397 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionResult() 00398 if self.action_feedback is None: 00399 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperGrabActionFeedback() 00400 end = 0 00401 _x = self 00402 start = end 00403 end += 12 00404 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00405 start = end 00406 end += 4 00407 (length,) = _struct_I.unpack(str[start:end]) 00408 start = end 00409 end += length 00410 self.action_goal.header.frame_id = str[start:end] 00411 _x = self 00412 start = end 00413 end += 8 00414 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00415 start = end 00416 end += 4 00417 (length,) = _struct_I.unpack(str[start:end]) 00418 start = end 00419 end += length 00420 self.action_goal.goal_id.id = str[start:end] 00421 _x = self 00422 start = end 00423 end += 20 00424 (_x.action_goal.goal.command.hardness_gain, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end]) 00425 start = end 00426 end += 4 00427 (length,) = _struct_I.unpack(str[start:end]) 00428 start = end 00429 end += length 00430 self.action_result.header.frame_id = str[start:end] 00431 _x = self 00432 start = end 00433 end += 8 00434 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00435 start = end 00436 end += 4 00437 (length,) = _struct_I.unpack(str[start:end]) 00438 start = end 00439 end += length 00440 self.action_result.status.goal_id.id = str[start:end] 00441 start = end 00442 end += 1 00443 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 00444 start = end 00445 end += 4 00446 (length,) = _struct_I.unpack(str[start:end]) 00447 start = end 00448 end += length 00449 self.action_result.status.text = str[start:end] 00450 _x = self 00451 start = end 00452 end += 13 00453 (_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end]) 00454 start = end 00455 end += 4 00456 (length,) = _struct_I.unpack(str[start:end]) 00457 start = end 00458 end += length 00459 self.action_feedback.header.frame_id = str[start:end] 00460 _x = self 00461 start = end 00462 end += 8 00463 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00464 start = end 00465 end += 4 00466 (length,) = _struct_I.unpack(str[start:end]) 00467 start = end 00468 end += length 00469 self.action_feedback.status.goal_id.id = str[start:end] 00470 start = end 00471 end += 1 00472 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00473 start = end 00474 end += 4 00475 (length,) = _struct_I.unpack(str[start:end]) 00476 start = end 00477 end += length 00478 self.action_feedback.status.text = str[start:end] 00479 start = end 00480 end += 1 00481 (self.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_b.unpack(str[start:end]) 00482 return self 00483 except struct.error as e: 00484 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00485 00486 _struct_I = roslib.message.struct_I 00487 _struct_B = struct.Struct("<B") 00488 _struct_3I = struct.Struct("<3I") 00489 _struct_b = struct.Struct("<b") 00490 _struct_b3I = struct.Struct("<b3I") 00491 _struct_d3I = struct.Struct("<d3I") 00492 _struct_2I = struct.Struct("<2I")