$search
00001 """autogenerated by genmsg_py from ReactivePlaceAction.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import trajectory_msgs.msg 00006 import object_manipulation_msgs.msg 00007 import roslib.rostime 00008 import actionlib_msgs.msg 00009 import geometry_msgs.msg 00010 import std_msgs.msg 00011 00012 class ReactivePlaceAction(roslib.message.Message): 00013 _md5sum = "ae0ee2c7f49f2e6b00a5b3a1cc9bde61" 00014 _type = "object_manipulation_msgs/ReactivePlaceAction" 00015 _has_header = False #flag to mark the presence of a Header object 00016 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00017 00018 ReactivePlaceActionGoal action_goal 00019 ReactivePlaceActionResult action_result 00020 ReactivePlaceActionFeedback action_feedback 00021 00022 ================================================================================ 00023 MSG: object_manipulation_msgs/ReactivePlaceActionGoal 00024 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00025 00026 Header header 00027 actionlib_msgs/GoalID goal_id 00028 ReactivePlaceGoal goal 00029 00030 ================================================================================ 00031 MSG: std_msgs/Header 00032 # Standard metadata for higher-level stamped data types. 00033 # This is generally used to communicate timestamped data 00034 # in a particular coordinate frame. 00035 # 00036 # sequence ID: consecutively increasing ID 00037 uint32 seq 00038 #Two-integer timestamp that is expressed as: 00039 # * stamp.secs: seconds (stamp_secs) since epoch 00040 # * stamp.nsecs: nanoseconds since stamp_secs 00041 # time-handling sugar is provided by the client library 00042 time stamp 00043 #Frame this data is associated with 00044 # 0: no frame 00045 # 1: global frame 00046 string frame_id 00047 00048 ================================================================================ 00049 MSG: actionlib_msgs/GoalID 00050 # The stamp should store the time at which this goal was requested. 00051 # It is used by an action server when it tries to preempt all 00052 # goals that were requested before a certain time 00053 time stamp 00054 00055 # The id provides a way to associate feedback and 00056 # result message with specific goal requests. The id 00057 # specified must be unique. 00058 string id 00059 00060 00061 ================================================================================ 00062 MSG: object_manipulation_msgs/ReactivePlaceGoal 00063 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00064 # an action for placing the object using tactile sensor feedback. 00065 # a reactive place starts from the current pose of the gripper and ends 00066 # at a desired place pose, presumably using the touch sensors along the way 00067 00068 # the name of the arm being used 00069 string arm_name 00070 00071 # the desired final place pose for the hand 00072 geometry_msgs/PoseStamped final_place_pose 00073 00074 # the joint trajectory to use for the place (if available) 00075 # this trajectory is expected to start at the current pose of the gripper 00076 # and end at the desired place pose 00077 trajectory_msgs/JointTrajectory trajectory 00078 00079 # the name of the support surface in the collision environment, if any 00080 string collision_support_surface_name 00081 00082 # the name in the collision environment of the object being placed, if any 00083 string collision_object_name 00084 00085 ================================================================================ 00086 MSG: geometry_msgs/PoseStamped 00087 # A Pose with reference coordinate frame and timestamp 00088 Header header 00089 Pose pose 00090 00091 ================================================================================ 00092 MSG: geometry_msgs/Pose 00093 # A representation of pose in free space, composed of postion and orientation. 00094 Point position 00095 Quaternion orientation 00096 00097 ================================================================================ 00098 MSG: geometry_msgs/Point 00099 # This contains the position of a point in free space 00100 float64 x 00101 float64 y 00102 float64 z 00103 00104 ================================================================================ 00105 MSG: geometry_msgs/Quaternion 00106 # This represents an orientation in free space in quaternion form. 00107 00108 float64 x 00109 float64 y 00110 float64 z 00111 float64 w 00112 00113 ================================================================================ 00114 MSG: trajectory_msgs/JointTrajectory 00115 Header header 00116 string[] joint_names 00117 JointTrajectoryPoint[] points 00118 ================================================================================ 00119 MSG: trajectory_msgs/JointTrajectoryPoint 00120 float64[] positions 00121 float64[] velocities 00122 float64[] accelerations 00123 duration time_from_start 00124 ================================================================================ 00125 MSG: object_manipulation_msgs/ReactivePlaceActionResult 00126 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00127 00128 Header header 00129 actionlib_msgs/GoalStatus status 00130 ReactivePlaceResult result 00131 00132 ================================================================================ 00133 MSG: actionlib_msgs/GoalStatus 00134 GoalID goal_id 00135 uint8 status 00136 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00137 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00138 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00139 # and has since completed its execution (Terminal State) 00140 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00141 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00142 # to some failure (Terminal State) 00143 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00144 # because the goal was unattainable or invalid (Terminal State) 00145 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00146 # and has not yet completed execution 00147 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00148 # but the action server has not yet confirmed that the goal is canceled 00149 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00150 # and was successfully cancelled (Terminal State) 00151 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00152 # sent over the wire by an action server 00153 00154 #Allow for the user to associate a string with GoalStatus for debugging 00155 string text 00156 00157 00158 ================================================================================ 00159 MSG: object_manipulation_msgs/ReactivePlaceResult 00160 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00161 00162 # the result of the reactive place attempt 00163 00164 ManipulationResult manipulation_result 00165 00166 00167 ================================================================================ 00168 MSG: object_manipulation_msgs/ManipulationResult 00169 # Result codes for manipulation tasks 00170 00171 # task completed as expected 00172 # generally means you can proceed as planned 00173 int32 SUCCESS = 1 00174 00175 # task not possible (e.g. out of reach or obstacles in the way) 00176 # generally means that the world was not disturbed, so you can try another task 00177 int32 UNFEASIBLE = -1 00178 00179 # task was thought possible, but failed due to unexpected events during execution 00180 # it is likely that the world was disturbed, so you are encouraged to refresh 00181 # your sensed world model before proceeding to another task 00182 int32 FAILED = -2 00183 00184 # a lower level error prevented task completion (e.g. joint controller not responding) 00185 # generally requires human attention 00186 int32 ERROR = -3 00187 00188 # means that at some point during execution we ended up in a state that the collision-aware 00189 # arm navigation module will not move out of. The world was likely not disturbed, but you 00190 # probably need a new collision map to move the arm out of the stuck position 00191 int32 ARM_MOVEMENT_PREVENTED = -4 00192 00193 # specific to grasp actions 00194 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested 00195 # it is likely that the collision environment will see collisions between the hand/object and the support surface 00196 int32 LIFT_FAILED = -5 00197 00198 # specific to place actions 00199 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested 00200 # it is likely that the collision environment will see collisions between the hand and the object 00201 int32 RETREAT_FAILED = -6 00202 00203 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else" 00204 int32 CANCELLED = -7 00205 00206 # the actual value of this error code 00207 int32 value 00208 00209 ================================================================================ 00210 MSG: object_manipulation_msgs/ReactivePlaceActionFeedback 00211 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00212 00213 Header header 00214 actionlib_msgs/GoalStatus status 00215 ReactivePlaceFeedback feedback 00216 00217 ================================================================================ 00218 MSG: object_manipulation_msgs/ReactivePlaceFeedback 00219 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00220 00221 # which phase the place is in 00222 00223 ManipulationPhase manipulation_phase 00224 00225 00226 ================================================================================ 00227 MSG: object_manipulation_msgs/ManipulationPhase 00228 int32 CHECKING_FEASIBILITY = 0 00229 int32 MOVING_TO_PREGRASP = 1 00230 int32 MOVING_TO_GRASP = 2 00231 int32 CLOSING = 3 00232 int32 ADJUSTING_GRASP = 4 00233 int32 LIFTING = 5 00234 int32 MOVING_WITH_OBJECT = 6 00235 int32 MOVING_TO_PLACE = 7 00236 int32 PLACING = 8 00237 int32 OPENING = 9 00238 int32 RETREATING = 10 00239 int32 MOVING_WITHOUT_OBJECT = 11 00240 int32 SHAKING = 12 00241 int32 SUCCEEDED = 13 00242 int32 FAILED = 14 00243 int32 ABORTED = 15 00244 int32 HOLDING_OBJECT = 16 00245 00246 int32 phase 00247 """ 00248 __slots__ = ['action_goal','action_result','action_feedback'] 00249 _slot_types = ['object_manipulation_msgs/ReactivePlaceActionGoal','object_manipulation_msgs/ReactivePlaceActionResult','object_manipulation_msgs/ReactivePlaceActionFeedback'] 00250 00251 def __init__(self, *args, **kwds): 00252 """ 00253 Constructor. Any message fields that are implicitly/explicitly 00254 set to None will be assigned a default value. The recommend 00255 use is keyword arguments as this is more robust to future message 00256 changes. You cannot mix in-order arguments and keyword arguments. 00257 00258 The available fields are: 00259 action_goal,action_result,action_feedback 00260 00261 @param args: complete set of field values, in .msg order 00262 @param kwds: use keyword arguments corresponding to message field names 00263 to set specific fields. 00264 """ 00265 if args or kwds: 00266 super(ReactivePlaceAction, self).__init__(*args, **kwds) 00267 #message fields cannot be None, assign default values for those that are 00268 if self.action_goal is None: 00269 self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal() 00270 if self.action_result is None: 00271 self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult() 00272 if self.action_feedback is None: 00273 self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback() 00274 else: 00275 self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal() 00276 self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult() 00277 self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback() 00278 00279 def _get_types(self): 00280 """ 00281 internal API method 00282 """ 00283 return self._slot_types 00284 00285 def serialize(self, buff): 00286 """ 00287 serialize message into buffer 00288 @param buff: buffer 00289 @type buff: StringIO 00290 """ 00291 try: 00292 _x = self 00293 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00294 _x = self.action_goal.header.frame_id 00295 length = len(_x) 00296 buff.write(struct.pack('<I%ss'%length, length, _x)) 00297 _x = self 00298 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00299 _x = self.action_goal.goal_id.id 00300 length = len(_x) 00301 buff.write(struct.pack('<I%ss'%length, length, _x)) 00302 _x = self.action_goal.goal.arm_name 00303 length = len(_x) 00304 buff.write(struct.pack('<I%ss'%length, length, _x)) 00305 _x = self 00306 buff.write(_struct_3I.pack(_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs)) 00307 _x = self.action_goal.goal.final_place_pose.header.frame_id 00308 length = len(_x) 00309 buff.write(struct.pack('<I%ss'%length, length, _x)) 00310 _x = self 00311 buff.write(_struct_7d3I.pack(_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs)) 00312 _x = self.action_goal.goal.trajectory.header.frame_id 00313 length = len(_x) 00314 buff.write(struct.pack('<I%ss'%length, length, _x)) 00315 length = len(self.action_goal.goal.trajectory.joint_names) 00316 buff.write(_struct_I.pack(length)) 00317 for val1 in self.action_goal.goal.trajectory.joint_names: 00318 length = len(val1) 00319 buff.write(struct.pack('<I%ss'%length, length, val1)) 00320 length = len(self.action_goal.goal.trajectory.points) 00321 buff.write(_struct_I.pack(length)) 00322 for val1 in self.action_goal.goal.trajectory.points: 00323 length = len(val1.positions) 00324 buff.write(_struct_I.pack(length)) 00325 pattern = '<%sd'%length 00326 buff.write(struct.pack(pattern, *val1.positions)) 00327 length = len(val1.velocities) 00328 buff.write(_struct_I.pack(length)) 00329 pattern = '<%sd'%length 00330 buff.write(struct.pack(pattern, *val1.velocities)) 00331 length = len(val1.accelerations) 00332 buff.write(_struct_I.pack(length)) 00333 pattern = '<%sd'%length 00334 buff.write(struct.pack(pattern, *val1.accelerations)) 00335 _v1 = val1.time_from_start 00336 _x = _v1 00337 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00338 _x = self.action_goal.goal.collision_support_surface_name 00339 length = len(_x) 00340 buff.write(struct.pack('<I%ss'%length, length, _x)) 00341 _x = self.action_goal.goal.collision_object_name 00342 length = len(_x) 00343 buff.write(struct.pack('<I%ss'%length, length, _x)) 00344 _x = self 00345 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00346 _x = self.action_result.header.frame_id 00347 length = len(_x) 00348 buff.write(struct.pack('<I%ss'%length, length, _x)) 00349 _x = self 00350 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00351 _x = self.action_result.status.goal_id.id 00352 length = len(_x) 00353 buff.write(struct.pack('<I%ss'%length, length, _x)) 00354 buff.write(_struct_B.pack(self.action_result.status.status)) 00355 _x = self.action_result.status.text 00356 length = len(_x) 00357 buff.write(struct.pack('<I%ss'%length, length, _x)) 00358 _x = self 00359 buff.write(_struct_i3I.pack(_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00360 _x = self.action_feedback.header.frame_id 00361 length = len(_x) 00362 buff.write(struct.pack('<I%ss'%length, length, _x)) 00363 _x = self 00364 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00365 _x = self.action_feedback.status.goal_id.id 00366 length = len(_x) 00367 buff.write(struct.pack('<I%ss'%length, length, _x)) 00368 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00369 _x = self.action_feedback.status.text 00370 length = len(_x) 00371 buff.write(struct.pack('<I%ss'%length, length, _x)) 00372 buff.write(_struct_i.pack(self.action_feedback.feedback.manipulation_phase.phase)) 00373 except struct.error as se: self._check_types(se) 00374 except TypeError as te: self._check_types(te) 00375 00376 def deserialize(self, str): 00377 """ 00378 unpack serialized message in str into this message instance 00379 @param str: byte array of serialized message 00380 @type str: str 00381 """ 00382 try: 00383 if self.action_goal is None: 00384 self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal() 00385 if self.action_result is None: 00386 self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult() 00387 if self.action_feedback is None: 00388 self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback() 00389 end = 0 00390 _x = self 00391 start = end 00392 end += 12 00393 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00394 start = end 00395 end += 4 00396 (length,) = _struct_I.unpack(str[start:end]) 00397 start = end 00398 end += length 00399 self.action_goal.header.frame_id = str[start:end] 00400 _x = self 00401 start = end 00402 end += 8 00403 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00404 start = end 00405 end += 4 00406 (length,) = _struct_I.unpack(str[start:end]) 00407 start = end 00408 end += length 00409 self.action_goal.goal_id.id = str[start:end] 00410 start = end 00411 end += 4 00412 (length,) = _struct_I.unpack(str[start:end]) 00413 start = end 00414 end += length 00415 self.action_goal.goal.arm_name = str[start:end] 00416 _x = self 00417 start = end 00418 end += 12 00419 (_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00420 start = end 00421 end += 4 00422 (length,) = _struct_I.unpack(str[start:end]) 00423 start = end 00424 end += length 00425 self.action_goal.goal.final_place_pose.header.frame_id = str[start:end] 00426 _x = self 00427 start = end 00428 end += 68 00429 (_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs,) = _struct_7d3I.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.goal.trajectory.header.frame_id = str[start:end] 00436 start = end 00437 end += 4 00438 (length,) = _struct_I.unpack(str[start:end]) 00439 self.action_goal.goal.trajectory.joint_names = [] 00440 for i in range(0, length): 00441 start = end 00442 end += 4 00443 (length,) = _struct_I.unpack(str[start:end]) 00444 start = end 00445 end += length 00446 val1 = str[start:end] 00447 self.action_goal.goal.trajectory.joint_names.append(val1) 00448 start = end 00449 end += 4 00450 (length,) = _struct_I.unpack(str[start:end]) 00451 self.action_goal.goal.trajectory.points = [] 00452 for i in range(0, length): 00453 val1 = trajectory_msgs.msg.JointTrajectoryPoint() 00454 start = end 00455 end += 4 00456 (length,) = _struct_I.unpack(str[start:end]) 00457 pattern = '<%sd'%length 00458 start = end 00459 end += struct.calcsize(pattern) 00460 val1.positions = struct.unpack(pattern, str[start:end]) 00461 start = end 00462 end += 4 00463 (length,) = _struct_I.unpack(str[start:end]) 00464 pattern = '<%sd'%length 00465 start = end 00466 end += struct.calcsize(pattern) 00467 val1.velocities = struct.unpack(pattern, str[start:end]) 00468 start = end 00469 end += 4 00470 (length,) = _struct_I.unpack(str[start:end]) 00471 pattern = '<%sd'%length 00472 start = end 00473 end += struct.calcsize(pattern) 00474 val1.accelerations = struct.unpack(pattern, str[start:end]) 00475 _v2 = val1.time_from_start 00476 _x = _v2 00477 start = end 00478 end += 8 00479 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00480 self.action_goal.goal.trajectory.points.append(val1) 00481 start = end 00482 end += 4 00483 (length,) = _struct_I.unpack(str[start:end]) 00484 start = end 00485 end += length 00486 self.action_goal.goal.collision_support_surface_name = str[start:end] 00487 start = end 00488 end += 4 00489 (length,) = _struct_I.unpack(str[start:end]) 00490 start = end 00491 end += length 00492 self.action_goal.goal.collision_object_name = str[start:end] 00493 _x = self 00494 start = end 00495 end += 12 00496 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00497 start = end 00498 end += 4 00499 (length,) = _struct_I.unpack(str[start:end]) 00500 start = end 00501 end += length 00502 self.action_result.header.frame_id = str[start:end] 00503 _x = self 00504 start = end 00505 end += 8 00506 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00507 start = end 00508 end += 4 00509 (length,) = _struct_I.unpack(str[start:end]) 00510 start = end 00511 end += length 00512 self.action_result.status.goal_id.id = str[start:end] 00513 start = end 00514 end += 1 00515 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 00516 start = end 00517 end += 4 00518 (length,) = _struct_I.unpack(str[start:end]) 00519 start = end 00520 end += length 00521 self.action_result.status.text = str[start:end] 00522 _x = self 00523 start = end 00524 end += 16 00525 (_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end]) 00526 start = end 00527 end += 4 00528 (length,) = _struct_I.unpack(str[start:end]) 00529 start = end 00530 end += length 00531 self.action_feedback.header.frame_id = str[start:end] 00532 _x = self 00533 start = end 00534 end += 8 00535 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00536 start = end 00537 end += 4 00538 (length,) = _struct_I.unpack(str[start:end]) 00539 start = end 00540 end += length 00541 self.action_feedback.status.goal_id.id = str[start:end] 00542 start = end 00543 end += 1 00544 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00545 start = end 00546 end += 4 00547 (length,) = _struct_I.unpack(str[start:end]) 00548 start = end 00549 end += length 00550 self.action_feedback.status.text = str[start:end] 00551 start = end 00552 end += 4 00553 (self.action_feedback.feedback.manipulation_phase.phase,) = _struct_i.unpack(str[start:end]) 00554 return self 00555 except struct.error as e: 00556 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00557 00558 00559 def serialize_numpy(self, buff, numpy): 00560 """ 00561 serialize message with numpy array types into buffer 00562 @param buff: buffer 00563 @type buff: StringIO 00564 @param numpy: numpy python module 00565 @type numpy module 00566 """ 00567 try: 00568 _x = self 00569 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00570 _x = self.action_goal.header.frame_id 00571 length = len(_x) 00572 buff.write(struct.pack('<I%ss'%length, length, _x)) 00573 _x = self 00574 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00575 _x = self.action_goal.goal_id.id 00576 length = len(_x) 00577 buff.write(struct.pack('<I%ss'%length, length, _x)) 00578 _x = self.action_goal.goal.arm_name 00579 length = len(_x) 00580 buff.write(struct.pack('<I%ss'%length, length, _x)) 00581 _x = self 00582 buff.write(_struct_3I.pack(_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs)) 00583 _x = self.action_goal.goal.final_place_pose.header.frame_id 00584 length = len(_x) 00585 buff.write(struct.pack('<I%ss'%length, length, _x)) 00586 _x = self 00587 buff.write(_struct_7d3I.pack(_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs)) 00588 _x = self.action_goal.goal.trajectory.header.frame_id 00589 length = len(_x) 00590 buff.write(struct.pack('<I%ss'%length, length, _x)) 00591 length = len(self.action_goal.goal.trajectory.joint_names) 00592 buff.write(_struct_I.pack(length)) 00593 for val1 in self.action_goal.goal.trajectory.joint_names: 00594 length = len(val1) 00595 buff.write(struct.pack('<I%ss'%length, length, val1)) 00596 length = len(self.action_goal.goal.trajectory.points) 00597 buff.write(_struct_I.pack(length)) 00598 for val1 in self.action_goal.goal.trajectory.points: 00599 length = len(val1.positions) 00600 buff.write(_struct_I.pack(length)) 00601 pattern = '<%sd'%length 00602 buff.write(val1.positions.tostring()) 00603 length = len(val1.velocities) 00604 buff.write(_struct_I.pack(length)) 00605 pattern = '<%sd'%length 00606 buff.write(val1.velocities.tostring()) 00607 length = len(val1.accelerations) 00608 buff.write(_struct_I.pack(length)) 00609 pattern = '<%sd'%length 00610 buff.write(val1.accelerations.tostring()) 00611 _v3 = val1.time_from_start 00612 _x = _v3 00613 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00614 _x = self.action_goal.goal.collision_support_surface_name 00615 length = len(_x) 00616 buff.write(struct.pack('<I%ss'%length, length, _x)) 00617 _x = self.action_goal.goal.collision_object_name 00618 length = len(_x) 00619 buff.write(struct.pack('<I%ss'%length, length, _x)) 00620 _x = self 00621 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00622 _x = self.action_result.header.frame_id 00623 length = len(_x) 00624 buff.write(struct.pack('<I%ss'%length, length, _x)) 00625 _x = self 00626 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00627 _x = self.action_result.status.goal_id.id 00628 length = len(_x) 00629 buff.write(struct.pack('<I%ss'%length, length, _x)) 00630 buff.write(_struct_B.pack(self.action_result.status.status)) 00631 _x = self.action_result.status.text 00632 length = len(_x) 00633 buff.write(struct.pack('<I%ss'%length, length, _x)) 00634 _x = self 00635 buff.write(_struct_i3I.pack(_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00636 _x = self.action_feedback.header.frame_id 00637 length = len(_x) 00638 buff.write(struct.pack('<I%ss'%length, length, _x)) 00639 _x = self 00640 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00641 _x = self.action_feedback.status.goal_id.id 00642 length = len(_x) 00643 buff.write(struct.pack('<I%ss'%length, length, _x)) 00644 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00645 _x = self.action_feedback.status.text 00646 length = len(_x) 00647 buff.write(struct.pack('<I%ss'%length, length, _x)) 00648 buff.write(_struct_i.pack(self.action_feedback.feedback.manipulation_phase.phase)) 00649 except struct.error as se: self._check_types(se) 00650 except TypeError as te: self._check_types(te) 00651 00652 def deserialize_numpy(self, str, numpy): 00653 """ 00654 unpack serialized message in str into this message instance using numpy for array types 00655 @param str: byte array of serialized message 00656 @type str: str 00657 @param numpy: numpy python module 00658 @type numpy: module 00659 """ 00660 try: 00661 if self.action_goal is None: 00662 self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal() 00663 if self.action_result is None: 00664 self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult() 00665 if self.action_feedback is None: 00666 self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback() 00667 end = 0 00668 _x = self 00669 start = end 00670 end += 12 00671 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00672 start = end 00673 end += 4 00674 (length,) = _struct_I.unpack(str[start:end]) 00675 start = end 00676 end += length 00677 self.action_goal.header.frame_id = str[start:end] 00678 _x = self 00679 start = end 00680 end += 8 00681 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00682 start = end 00683 end += 4 00684 (length,) = _struct_I.unpack(str[start:end]) 00685 start = end 00686 end += length 00687 self.action_goal.goal_id.id = str[start:end] 00688 start = end 00689 end += 4 00690 (length,) = _struct_I.unpack(str[start:end]) 00691 start = end 00692 end += length 00693 self.action_goal.goal.arm_name = str[start:end] 00694 _x = self 00695 start = end 00696 end += 12 00697 (_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00698 start = end 00699 end += 4 00700 (length,) = _struct_I.unpack(str[start:end]) 00701 start = end 00702 end += length 00703 self.action_goal.goal.final_place_pose.header.frame_id = str[start:end] 00704 _x = self 00705 start = end 00706 end += 68 00707 (_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end]) 00708 start = end 00709 end += 4 00710 (length,) = _struct_I.unpack(str[start:end]) 00711 start = end 00712 end += length 00713 self.action_goal.goal.trajectory.header.frame_id = str[start:end] 00714 start = end 00715 end += 4 00716 (length,) = _struct_I.unpack(str[start:end]) 00717 self.action_goal.goal.trajectory.joint_names = [] 00718 for i in range(0, length): 00719 start = end 00720 end += 4 00721 (length,) = _struct_I.unpack(str[start:end]) 00722 start = end 00723 end += length 00724 val1 = str[start:end] 00725 self.action_goal.goal.trajectory.joint_names.append(val1) 00726 start = end 00727 end += 4 00728 (length,) = _struct_I.unpack(str[start:end]) 00729 self.action_goal.goal.trajectory.points = [] 00730 for i in range(0, length): 00731 val1 = trajectory_msgs.msg.JointTrajectoryPoint() 00732 start = end 00733 end += 4 00734 (length,) = _struct_I.unpack(str[start:end]) 00735 pattern = '<%sd'%length 00736 start = end 00737 end += struct.calcsize(pattern) 00738 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00739 start = end 00740 end += 4 00741 (length,) = _struct_I.unpack(str[start:end]) 00742 pattern = '<%sd'%length 00743 start = end 00744 end += struct.calcsize(pattern) 00745 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00746 start = end 00747 end += 4 00748 (length,) = _struct_I.unpack(str[start:end]) 00749 pattern = '<%sd'%length 00750 start = end 00751 end += struct.calcsize(pattern) 00752 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00753 _v4 = val1.time_from_start 00754 _x = _v4 00755 start = end 00756 end += 8 00757 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00758 self.action_goal.goal.trajectory.points.append(val1) 00759 start = end 00760 end += 4 00761 (length,) = _struct_I.unpack(str[start:end]) 00762 start = end 00763 end += length 00764 self.action_goal.goal.collision_support_surface_name = str[start:end] 00765 start = end 00766 end += 4 00767 (length,) = _struct_I.unpack(str[start:end]) 00768 start = end 00769 end += length 00770 self.action_goal.goal.collision_object_name = str[start:end] 00771 _x = self 00772 start = end 00773 end += 12 00774 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00775 start = end 00776 end += 4 00777 (length,) = _struct_I.unpack(str[start:end]) 00778 start = end 00779 end += length 00780 self.action_result.header.frame_id = str[start:end] 00781 _x = self 00782 start = end 00783 end += 8 00784 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00785 start = end 00786 end += 4 00787 (length,) = _struct_I.unpack(str[start:end]) 00788 start = end 00789 end += length 00790 self.action_result.status.goal_id.id = str[start:end] 00791 start = end 00792 end += 1 00793 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 00794 start = end 00795 end += 4 00796 (length,) = _struct_I.unpack(str[start:end]) 00797 start = end 00798 end += length 00799 self.action_result.status.text = str[start:end] 00800 _x = self 00801 start = end 00802 end += 16 00803 (_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end]) 00804 start = end 00805 end += 4 00806 (length,) = _struct_I.unpack(str[start:end]) 00807 start = end 00808 end += length 00809 self.action_feedback.header.frame_id = str[start:end] 00810 _x = self 00811 start = end 00812 end += 8 00813 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00814 start = end 00815 end += 4 00816 (length,) = _struct_I.unpack(str[start:end]) 00817 start = end 00818 end += length 00819 self.action_feedback.status.goal_id.id = str[start:end] 00820 start = end 00821 end += 1 00822 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00823 start = end 00824 end += 4 00825 (length,) = _struct_I.unpack(str[start:end]) 00826 start = end 00827 end += length 00828 self.action_feedback.status.text = str[start:end] 00829 start = end 00830 end += 4 00831 (self.action_feedback.feedback.manipulation_phase.phase,) = _struct_i.unpack(str[start:end]) 00832 return self 00833 except struct.error as e: 00834 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00835 00836 _struct_I = roslib.message.struct_I 00837 _struct_7d3I = struct.Struct("<7d3I") 00838 _struct_B = struct.Struct("<B") 00839 _struct_i = struct.Struct("<i") 00840 _struct_i3I = struct.Struct("<i3I") 00841 _struct_2I = struct.Struct("<2I") 00842 _struct_3I = struct.Struct("<3I") 00843 _struct_2i = struct.Struct("<2i")