$search
00001 """autogenerated by genmsg_py from PR2GripperForceServoAction.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 PR2GripperForceServoAction(roslib.message.Message): 00011 _md5sum = "0540bb7603e65b3df5c9dc87b150e790" 00012 _type = "pr2_gripper_sensor_msgs/PR2GripperForceServoAction" 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 PR2GripperForceServoActionGoal action_goal 00017 PR2GripperForceServoActionResult action_result 00018 PR2GripperForceServoActionFeedback action_feedback 00019 00020 ================================================================================ 00021 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionGoal 00022 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00023 00024 Header header 00025 actionlib_msgs/GoalID goal_id 00026 PR2GripperForceServoGoal 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/PR2GripperForceServoGoal 00061 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00062 # Action to launch the gripper into force servoing mode 00063 00064 #goals 00065 PR2GripperForceServoCommand command 00066 00067 ================================================================================ 00068 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoCommand 00069 # the amount of fingertip force (in Newtons) to apply. 00070 # NOTE: the joint will squeeze until each finger reaches this level 00071 # values < 0 (opening force) are ignored 00072 # 00073 # 10 N can crack an egg or crush a soda can. 00074 # 15 N can firmly pick up a can of soup. 00075 # Experiment on your own. 00076 # 00077 float64 fingertip_force 00078 ================================================================================ 00079 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionResult 00080 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00081 00082 Header header 00083 actionlib_msgs/GoalStatus status 00084 PR2GripperForceServoResult result 00085 00086 ================================================================================ 00087 MSG: actionlib_msgs/GoalStatus 00088 GoalID goal_id 00089 uint8 status 00090 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00091 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00092 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00093 # and has since completed its execution (Terminal State) 00094 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00095 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00096 # to some failure (Terminal State) 00097 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00098 # because the goal was unattainable or invalid (Terminal State) 00099 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00100 # and has not yet completed execution 00101 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00102 # but the action server has not yet confirmed that the goal is canceled 00103 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00104 # and was successfully cancelled (Terminal State) 00105 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00106 # sent over the wire by an action server 00107 00108 #Allow for the user to associate a string with GoalStatus for debugging 00109 string text 00110 00111 00112 ================================================================================ 00113 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoResult 00114 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00115 00116 #result 00117 PR2GripperForceServoData data 00118 00119 00120 ================================================================================ 00121 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoData 00122 # Time the data was recorded at 00123 time stamp 00124 00125 # the force experienced by the finger Pads (N) 00126 # NOTE:this ignores data from the edges of the finger pressure 00127 float64 left_fingertip_pad_force 00128 float64 right_fingertip_pad_force 00129 00130 # the current gripper virtual parallel joint effort (in N) 00131 float64 joint_effort 00132 00133 # true when the gripper is no longer moving 00134 # and we have reached the desired force level 00135 bool force_achieved 00136 00137 00138 # the control state of our realtime controller 00139 PR2GripperSensorRTState rtstate 00140 00141 ================================================================================ 00142 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState 00143 # the control state of our realtime controller 00144 int8 realtime_controller_state 00145 00146 # predefined values to indicate our realtime_controller_state 00147 int8 DISABLED = 0 00148 int8 POSITION_SERVO = 3 00149 int8 FORCE_SERVO = 4 00150 int8 FIND_CONTACT = 5 00151 int8 SLIP_SERVO = 6 00152 ================================================================================ 00153 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionFeedback 00154 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00155 00156 Header header 00157 actionlib_msgs/GoalStatus status 00158 PR2GripperForceServoFeedback feedback 00159 00160 ================================================================================ 00161 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoFeedback 00162 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00163 00164 #feedback 00165 PR2GripperForceServoData data 00166 00167 """ 00168 __slots__ = ['action_goal','action_result','action_feedback'] 00169 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperForceServoActionGoal','pr2_gripper_sensor_msgs/PR2GripperForceServoActionResult','pr2_gripper_sensor_msgs/PR2GripperForceServoActionFeedback'] 00170 00171 def __init__(self, *args, **kwds): 00172 """ 00173 Constructor. Any message fields that are implicitly/explicitly 00174 set to None will be assigned a default value. The recommend 00175 use is keyword arguments as this is more robust to future message 00176 changes. You cannot mix in-order arguments and keyword arguments. 00177 00178 The available fields are: 00179 action_goal,action_result,action_feedback 00180 00181 @param args: complete set of field values, in .msg order 00182 @param kwds: use keyword arguments corresponding to message field names 00183 to set specific fields. 00184 """ 00185 if args or kwds: 00186 super(PR2GripperForceServoAction, self).__init__(*args, **kwds) 00187 #message fields cannot be None, assign default values for those that are 00188 if self.action_goal is None: 00189 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal() 00190 if self.action_result is None: 00191 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult() 00192 if self.action_feedback is None: 00193 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback() 00194 else: 00195 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal() 00196 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult() 00197 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback() 00198 00199 def _get_types(self): 00200 """ 00201 internal API method 00202 """ 00203 return self._slot_types 00204 00205 def serialize(self, buff): 00206 """ 00207 serialize message into buffer 00208 @param buff: buffer 00209 @type buff: StringIO 00210 """ 00211 try: 00212 _x = self 00213 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00214 _x = self.action_goal.header.frame_id 00215 length = len(_x) 00216 buff.write(struct.pack('<I%ss'%length, length, _x)) 00217 _x = self 00218 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00219 _x = self.action_goal.goal_id.id 00220 length = len(_x) 00221 buff.write(struct.pack('<I%ss'%length, length, _x)) 00222 _x = self 00223 buff.write(_struct_d3I.pack(_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00224 _x = self.action_result.header.frame_id 00225 length = len(_x) 00226 buff.write(struct.pack('<I%ss'%length, length, _x)) 00227 _x = self 00228 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00229 _x = self.action_result.status.goal_id.id 00230 length = len(_x) 00231 buff.write(struct.pack('<I%ss'%length, length, _x)) 00232 buff.write(_struct_B.pack(self.action_result.status.status)) 00233 _x = self.action_result.status.text 00234 length = len(_x) 00235 buff.write(struct.pack('<I%ss'%length, length, _x)) 00236 _x = self 00237 buff.write(_struct_2I3dBb3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.force_achieved, _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)) 00238 _x = self.action_feedback.header.frame_id 00239 length = len(_x) 00240 buff.write(struct.pack('<I%ss'%length, length, _x)) 00241 _x = self 00242 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00243 _x = self.action_feedback.status.goal_id.id 00244 length = len(_x) 00245 buff.write(struct.pack('<I%ss'%length, length, _x)) 00246 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00247 _x = self.action_feedback.status.text 00248 length = len(_x) 00249 buff.write(struct.pack('<I%ss'%length, length, _x)) 00250 _x = self 00251 buff.write(_struct_2I3dBb.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state)) 00252 except struct.error as se: self._check_types(se) 00253 except TypeError as te: self._check_types(te) 00254 00255 def deserialize(self, str): 00256 """ 00257 unpack serialized message in str into this message instance 00258 @param str: byte array of serialized message 00259 @type str: str 00260 """ 00261 try: 00262 if self.action_goal is None: 00263 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal() 00264 if self.action_result is None: 00265 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult() 00266 if self.action_feedback is None: 00267 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback() 00268 end = 0 00269 _x = self 00270 start = end 00271 end += 12 00272 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00273 start = end 00274 end += 4 00275 (length,) = _struct_I.unpack(str[start:end]) 00276 start = end 00277 end += length 00278 self.action_goal.header.frame_id = str[start:end] 00279 _x = self 00280 start = end 00281 end += 8 00282 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00283 start = end 00284 end += 4 00285 (length,) = _struct_I.unpack(str[start:end]) 00286 start = end 00287 end += length 00288 self.action_goal.goal_id.id = str[start:end] 00289 _x = self 00290 start = end 00291 end += 20 00292 (_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.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.action_result.header.frame_id = str[start:end] 00299 _x = self 00300 start = end 00301 end += 8 00302 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.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.action_result.status.goal_id.id = str[start:end] 00309 start = end 00310 end += 1 00311 (self.action_result.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.action_result.status.text = str[start:end] 00318 _x = self 00319 start = end 00320 end += 46 00321 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.force_achieved, _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_2I3dBb3I.unpack(str[start:end]) 00322 self.action_result.result.data.force_achieved = bool(self.action_result.result.data.force_achieved) 00323 start = end 00324 end += 4 00325 (length,) = _struct_I.unpack(str[start:end]) 00326 start = end 00327 end += length 00328 self.action_feedback.header.frame_id = str[start:end] 00329 _x = self 00330 start = end 00331 end += 8 00332 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00333 start = end 00334 end += 4 00335 (length,) = _struct_I.unpack(str[start:end]) 00336 start = end 00337 end += length 00338 self.action_feedback.status.goal_id.id = str[start:end] 00339 start = end 00340 end += 1 00341 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00342 start = end 00343 end += 4 00344 (length,) = _struct_I.unpack(str[start:end]) 00345 start = end 00346 end += length 00347 self.action_feedback.status.text = str[start:end] 00348 _x = self 00349 start = end 00350 end += 34 00351 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3dBb.unpack(str[start:end]) 00352 self.action_feedback.feedback.data.force_achieved = bool(self.action_feedback.feedback.data.force_achieved) 00353 return self 00354 except struct.error as e: 00355 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00356 00357 00358 def serialize_numpy(self, buff, numpy): 00359 """ 00360 serialize message with numpy array types into buffer 00361 @param buff: buffer 00362 @type buff: StringIO 00363 @param numpy: numpy python module 00364 @type numpy module 00365 """ 00366 try: 00367 _x = self 00368 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00369 _x = self.action_goal.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_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00374 _x = self.action_goal.goal_id.id 00375 length = len(_x) 00376 buff.write(struct.pack('<I%ss'%length, length, _x)) 00377 _x = self 00378 buff.write(_struct_d3I.pack(_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00379 _x = self.action_result.header.frame_id 00380 length = len(_x) 00381 buff.write(struct.pack('<I%ss'%length, length, _x)) 00382 _x = self 00383 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00384 _x = self.action_result.status.goal_id.id 00385 length = len(_x) 00386 buff.write(struct.pack('<I%ss'%length, length, _x)) 00387 buff.write(_struct_B.pack(self.action_result.status.status)) 00388 _x = self.action_result.status.text 00389 length = len(_x) 00390 buff.write(struct.pack('<I%ss'%length, length, _x)) 00391 _x = self 00392 buff.write(_struct_2I3dBb3I.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.force_achieved, _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)) 00393 _x = self.action_feedback.header.frame_id 00394 length = len(_x) 00395 buff.write(struct.pack('<I%ss'%length, length, _x)) 00396 _x = self 00397 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00398 _x = self.action_feedback.status.goal_id.id 00399 length = len(_x) 00400 buff.write(struct.pack('<I%ss'%length, length, _x)) 00401 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00402 _x = self.action_feedback.status.text 00403 length = len(_x) 00404 buff.write(struct.pack('<I%ss'%length, length, _x)) 00405 _x = self 00406 buff.write(_struct_2I3dBb.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state)) 00407 except struct.error as se: self._check_types(se) 00408 except TypeError as te: self._check_types(te) 00409 00410 def deserialize_numpy(self, str, numpy): 00411 """ 00412 unpack serialized message in str into this message instance using numpy for array types 00413 @param str: byte array of serialized message 00414 @type str: str 00415 @param numpy: numpy python module 00416 @type numpy: module 00417 """ 00418 try: 00419 if self.action_goal is None: 00420 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionGoal() 00421 if self.action_result is None: 00422 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionResult() 00423 if self.action_feedback is None: 00424 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperForceServoActionFeedback() 00425 end = 0 00426 _x = self 00427 start = end 00428 end += 12 00429 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00430 start = end 00431 end += 4 00432 (length,) = _struct_I.unpack(str[start:end]) 00433 start = end 00434 end += length 00435 self.action_goal.header.frame_id = str[start:end] 00436 _x = self 00437 start = end 00438 end += 8 00439 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00440 start = end 00441 end += 4 00442 (length,) = _struct_I.unpack(str[start:end]) 00443 start = end 00444 end += length 00445 self.action_goal.goal_id.id = str[start:end] 00446 _x = self 00447 start = end 00448 end += 20 00449 (_x.action_goal.goal.command.fingertip_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_d3I.unpack(str[start:end]) 00450 start = end 00451 end += 4 00452 (length,) = _struct_I.unpack(str[start:end]) 00453 start = end 00454 end += length 00455 self.action_result.header.frame_id = str[start:end] 00456 _x = self 00457 start = end 00458 end += 8 00459 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00460 start = end 00461 end += 4 00462 (length,) = _struct_I.unpack(str[start:end]) 00463 start = end 00464 end += length 00465 self.action_result.status.goal_id.id = str[start:end] 00466 start = end 00467 end += 1 00468 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 00469 start = end 00470 end += 4 00471 (length,) = _struct_I.unpack(str[start:end]) 00472 start = end 00473 end += length 00474 self.action_result.status.text = str[start:end] 00475 _x = self 00476 start = end 00477 end += 46 00478 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.left_fingertip_pad_force, _x.action_result.result.data.right_fingertip_pad_force, _x.action_result.result.data.joint_effort, _x.action_result.result.data.force_achieved, _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_2I3dBb3I.unpack(str[start:end]) 00479 self.action_result.result.data.force_achieved = bool(self.action_result.result.data.force_achieved) 00480 start = end 00481 end += 4 00482 (length,) = _struct_I.unpack(str[start:end]) 00483 start = end 00484 end += length 00485 self.action_feedback.header.frame_id = str[start:end] 00486 _x = self 00487 start = end 00488 end += 8 00489 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00490 start = end 00491 end += 4 00492 (length,) = _struct_I.unpack(str[start:end]) 00493 start = end 00494 end += length 00495 self.action_feedback.status.goal_id.id = str[start:end] 00496 start = end 00497 end += 1 00498 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00499 start = end 00500 end += 4 00501 (length,) = _struct_I.unpack(str[start:end]) 00502 start = end 00503 end += length 00504 self.action_feedback.status.text = str[start:end] 00505 _x = self 00506 start = end 00507 end += 34 00508 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.left_fingertip_pad_force, _x.action_feedback.feedback.data.right_fingertip_pad_force, _x.action_feedback.feedback.data.joint_effort, _x.action_feedback.feedback.data.force_achieved, _x.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_2I3dBb.unpack(str[start:end]) 00509 self.action_feedback.feedback.data.force_achieved = bool(self.action_feedback.feedback.data.force_achieved) 00510 return self 00511 except struct.error as e: 00512 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00513 00514 _struct_I = roslib.message.struct_I 00515 _struct_B = struct.Struct("<B") 00516 _struct_3I = struct.Struct("<3I") 00517 _struct_2I3dBb3I = struct.Struct("<2I3dBb3I") 00518 _struct_d3I = struct.Struct("<d3I") 00519 _struct_2I3dBb = struct.Struct("<2I3dBb") 00520 _struct_2I = struct.Struct("<2I")