$search
00001 """autogenerated by genmsg_py from ModelObjectInHandAction.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import roslib.rostime 00006 import actionlib_msgs.msg 00007 import pr2_create_object_model.msg 00008 import geometry_msgs.msg 00009 import sensor_msgs.msg 00010 import std_msgs.msg 00011 00012 class ModelObjectInHandAction(roslib.message.Message): 00013 _md5sum = "48f36e754cdbe5df61db81cd410cecf9" 00014 _type = "pr2_create_object_model/ModelObjectInHandAction" 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 ModelObjectInHandActionGoal action_goal 00019 ModelObjectInHandActionResult action_result 00020 ModelObjectInHandActionFeedback action_feedback 00021 00022 ================================================================================ 00023 MSG: pr2_create_object_model/ModelObjectInHandActionGoal 00024 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00025 00026 Header header 00027 actionlib_msgs/GoalID goal_id 00028 ModelObjectInHandGoal 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: pr2_create_object_model/ModelObjectInHandGoal 00063 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00064 # which arm to use 00065 string arm_name 00066 00067 # the relative motion in which to move the gripper to get it clear of objects 00068 #(if left unfilled, will not move) 00069 geometry_msgs/Vector3Stamped clear_move 00070 00071 # the pose to go to for rotating (if left unfilled, will not go) 00072 geometry_msgs/PoseStamped rotate_pose 00073 00074 # whether to rotate the object at rotate_pose to build up the model 00075 uint8 rotate_object 00076 00077 # whether to add the object to the collision map 00078 uint8 add_to_collision_map 00079 00080 # whether to keep the object level while rotating 00081 uint8 keep_level 00082 00083 00084 ================================================================================ 00085 MSG: geometry_msgs/Vector3Stamped 00086 # This represents a Vector3 with reference coordinate frame and timestamp 00087 Header header 00088 Vector3 vector 00089 00090 ================================================================================ 00091 MSG: geometry_msgs/Vector3 00092 # This represents a vector in free space. 00093 00094 float64 x 00095 float64 y 00096 float64 z 00097 ================================================================================ 00098 MSG: geometry_msgs/PoseStamped 00099 # A Pose with reference coordinate frame and timestamp 00100 Header header 00101 Pose pose 00102 00103 ================================================================================ 00104 MSG: geometry_msgs/Pose 00105 # A representation of pose in free space, composed of postion and orientation. 00106 Point position 00107 Quaternion orientation 00108 00109 ================================================================================ 00110 MSG: geometry_msgs/Point 00111 # This contains the position of a point in free space 00112 float64 x 00113 float64 y 00114 float64 z 00115 00116 ================================================================================ 00117 MSG: geometry_msgs/Quaternion 00118 # This represents an orientation in free space in quaternion form. 00119 00120 float64 x 00121 float64 y 00122 float64 z 00123 float64 w 00124 00125 ================================================================================ 00126 MSG: pr2_create_object_model/ModelObjectInHandActionResult 00127 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00128 00129 Header header 00130 actionlib_msgs/GoalStatus status 00131 ModelObjectInHandResult result 00132 00133 ================================================================================ 00134 MSG: actionlib_msgs/GoalStatus 00135 GoalID goal_id 00136 uint8 status 00137 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00138 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00139 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00140 # and has since completed its execution (Terminal State) 00141 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00142 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00143 # to some failure (Terminal State) 00144 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00145 # because the goal was unattainable or invalid (Terminal State) 00146 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00147 # and has not yet completed execution 00148 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00149 # but the action server has not yet confirmed that the goal is canceled 00150 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00151 # and was successfully cancelled (Terminal State) 00152 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00153 # sent over the wire by an action server 00154 00155 #Allow for the user to associate a string with GoalStatus for debugging 00156 string text 00157 00158 00159 ================================================================================ 00160 MSG: pr2_create_object_model/ModelObjectInHandResult 00161 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00162 00163 # the resulting object point cloud 00164 sensor_msgs/PointCloud2 cluster 00165 00166 # the resulting collision name, if added to the collision map 00167 string collision_name 00168 00169 00170 ================================================================================ 00171 MSG: sensor_msgs/PointCloud2 00172 # This message holds a collection of N-dimensional points, which may 00173 # contain additional information such as normals, intensity, etc. The 00174 # point data is stored as a binary blob, its layout described by the 00175 # contents of the "fields" array. 00176 00177 # The point cloud data may be organized 2d (image-like) or 1d 00178 # (unordered). Point clouds organized as 2d images may be produced by 00179 # camera depth sensors such as stereo or time-of-flight. 00180 00181 # Time of sensor data acquisition, and the coordinate frame ID (for 3d 00182 # points). 00183 Header header 00184 00185 # 2D structure of the point cloud. If the cloud is unordered, height is 00186 # 1 and width is the length of the point cloud. 00187 uint32 height 00188 uint32 width 00189 00190 # Describes the channels and their layout in the binary data blob. 00191 PointField[] fields 00192 00193 bool is_bigendian # Is this data bigendian? 00194 uint32 point_step # Length of a point in bytes 00195 uint32 row_step # Length of a row in bytes 00196 uint8[] data # Actual point data, size is (row_step*height) 00197 00198 bool is_dense # True if there are no invalid points 00199 00200 ================================================================================ 00201 MSG: sensor_msgs/PointField 00202 # This message holds the description of one point entry in the 00203 # PointCloud2 message format. 00204 uint8 INT8 = 1 00205 uint8 UINT8 = 2 00206 uint8 INT16 = 3 00207 uint8 UINT16 = 4 00208 uint8 INT32 = 5 00209 uint8 UINT32 = 6 00210 uint8 FLOAT32 = 7 00211 uint8 FLOAT64 = 8 00212 00213 string name # Name of field 00214 uint32 offset # Offset from start of point struct 00215 uint8 datatype # Datatype enumeration, see above 00216 uint32 count # How many elements in the field 00217 00218 ================================================================================ 00219 MSG: pr2_create_object_model/ModelObjectInHandActionFeedback 00220 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00221 00222 Header header 00223 actionlib_msgs/GoalStatus status 00224 ModelObjectInHandFeedback feedback 00225 00226 ================================================================================ 00227 MSG: pr2_create_object_model/ModelObjectInHandFeedback 00228 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00229 00230 # which phase the process is in 00231 int32 phase 00232 int32 BEFORE_MOVE=0 00233 int32 CLEAR_MOVE=1 00234 int32 MOVE_TO_ROTATE_POSE=2 00235 int32 ROTATING=3 00236 int32 DONE=4 00237 00238 # how many rotate-poses have we gone to/are we in now 00239 int32 rotate_ind 00240 00241 00242 """ 00243 __slots__ = ['action_goal','action_result','action_feedback'] 00244 _slot_types = ['pr2_create_object_model/ModelObjectInHandActionGoal','pr2_create_object_model/ModelObjectInHandActionResult','pr2_create_object_model/ModelObjectInHandActionFeedback'] 00245 00246 def __init__(self, *args, **kwds): 00247 """ 00248 Constructor. Any message fields that are implicitly/explicitly 00249 set to None will be assigned a default value. The recommend 00250 use is keyword arguments as this is more robust to future message 00251 changes. You cannot mix in-order arguments and keyword arguments. 00252 00253 The available fields are: 00254 action_goal,action_result,action_feedback 00255 00256 @param args: complete set of field values, in .msg order 00257 @param kwds: use keyword arguments corresponding to message field names 00258 to set specific fields. 00259 """ 00260 if args or kwds: 00261 super(ModelObjectInHandAction, self).__init__(*args, **kwds) 00262 #message fields cannot be None, assign default values for those that are 00263 if self.action_goal is None: 00264 self.action_goal = pr2_create_object_model.msg.ModelObjectInHandActionGoal() 00265 if self.action_result is None: 00266 self.action_result = pr2_create_object_model.msg.ModelObjectInHandActionResult() 00267 if self.action_feedback is None: 00268 self.action_feedback = pr2_create_object_model.msg.ModelObjectInHandActionFeedback() 00269 else: 00270 self.action_goal = pr2_create_object_model.msg.ModelObjectInHandActionGoal() 00271 self.action_result = pr2_create_object_model.msg.ModelObjectInHandActionResult() 00272 self.action_feedback = pr2_create_object_model.msg.ModelObjectInHandActionFeedback() 00273 00274 def _get_types(self): 00275 """ 00276 internal API method 00277 """ 00278 return self._slot_types 00279 00280 def serialize(self, buff): 00281 """ 00282 serialize message into buffer 00283 @param buff: buffer 00284 @type buff: StringIO 00285 """ 00286 try: 00287 _x = self 00288 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00289 _x = self.action_goal.header.frame_id 00290 length = len(_x) 00291 buff.write(struct.pack('<I%ss'%length, length, _x)) 00292 _x = self 00293 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00294 _x = self.action_goal.goal_id.id 00295 length = len(_x) 00296 buff.write(struct.pack('<I%ss'%length, length, _x)) 00297 _x = self.action_goal.goal.arm_name 00298 length = len(_x) 00299 buff.write(struct.pack('<I%ss'%length, length, _x)) 00300 _x = self 00301 buff.write(_struct_3I.pack(_x.action_goal.goal.clear_move.header.seq, _x.action_goal.goal.clear_move.header.stamp.secs, _x.action_goal.goal.clear_move.header.stamp.nsecs)) 00302 _x = self.action_goal.goal.clear_move.header.frame_id 00303 length = len(_x) 00304 buff.write(struct.pack('<I%ss'%length, length, _x)) 00305 _x = self 00306 buff.write(_struct_3d3I.pack(_x.action_goal.goal.clear_move.vector.x, _x.action_goal.goal.clear_move.vector.y, _x.action_goal.goal.clear_move.vector.z, _x.action_goal.goal.rotate_pose.header.seq, _x.action_goal.goal.rotate_pose.header.stamp.secs, _x.action_goal.goal.rotate_pose.header.stamp.nsecs)) 00307 _x = self.action_goal.goal.rotate_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_7d3B3I.pack(_x.action_goal.goal.rotate_pose.pose.position.x, _x.action_goal.goal.rotate_pose.pose.position.y, _x.action_goal.goal.rotate_pose.pose.position.z, _x.action_goal.goal.rotate_pose.pose.orientation.x, _x.action_goal.goal.rotate_pose.pose.orientation.y, _x.action_goal.goal.rotate_pose.pose.orientation.z, _x.action_goal.goal.rotate_pose.pose.orientation.w, _x.action_goal.goal.rotate_object, _x.action_goal.goal.add_to_collision_map, _x.action_goal.goal.keep_level, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00312 _x = self.action_result.header.frame_id 00313 length = len(_x) 00314 buff.write(struct.pack('<I%ss'%length, length, _x)) 00315 _x = self 00316 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00317 _x = self.action_result.status.goal_id.id 00318 length = len(_x) 00319 buff.write(struct.pack('<I%ss'%length, length, _x)) 00320 buff.write(_struct_B.pack(self.action_result.status.status)) 00321 _x = self.action_result.status.text 00322 length = len(_x) 00323 buff.write(struct.pack('<I%ss'%length, length, _x)) 00324 _x = self 00325 buff.write(_struct_3I.pack(_x.action_result.result.cluster.header.seq, _x.action_result.result.cluster.header.stamp.secs, _x.action_result.result.cluster.header.stamp.nsecs)) 00326 _x = self.action_result.result.cluster.header.frame_id 00327 length = len(_x) 00328 buff.write(struct.pack('<I%ss'%length, length, _x)) 00329 _x = self 00330 buff.write(_struct_2I.pack(_x.action_result.result.cluster.height, _x.action_result.result.cluster.width)) 00331 length = len(self.action_result.result.cluster.fields) 00332 buff.write(_struct_I.pack(length)) 00333 for val1 in self.action_result.result.cluster.fields: 00334 _x = val1.name 00335 length = len(_x) 00336 buff.write(struct.pack('<I%ss'%length, length, _x)) 00337 _x = val1 00338 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 00339 _x = self 00340 buff.write(_struct_B2I.pack(_x.action_result.result.cluster.is_bigendian, _x.action_result.result.cluster.point_step, _x.action_result.result.cluster.row_step)) 00341 _x = self.action_result.result.cluster.data 00342 length = len(_x) 00343 # - if encoded as a list instead, serialize as bytes instead of string 00344 if type(_x) in [list, tuple]: 00345 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00346 else: 00347 buff.write(struct.pack('<I%ss'%length, length, _x)) 00348 buff.write(_struct_B.pack(self.action_result.result.cluster.is_dense)) 00349 _x = self.action_result.result.collision_name 00350 length = len(_x) 00351 buff.write(struct.pack('<I%ss'%length, length, _x)) 00352 _x = self 00353 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00354 _x = self.action_feedback.header.frame_id 00355 length = len(_x) 00356 buff.write(struct.pack('<I%ss'%length, length, _x)) 00357 _x = self 00358 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00359 _x = self.action_feedback.status.goal_id.id 00360 length = len(_x) 00361 buff.write(struct.pack('<I%ss'%length, length, _x)) 00362 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00363 _x = self.action_feedback.status.text 00364 length = len(_x) 00365 buff.write(struct.pack('<I%ss'%length, length, _x)) 00366 _x = self 00367 buff.write(_struct_2i.pack(_x.action_feedback.feedback.phase, _x.action_feedback.feedback.rotate_ind)) 00368 except struct.error as se: self._check_types(se) 00369 except TypeError as te: self._check_types(te) 00370 00371 def deserialize(self, str): 00372 """ 00373 unpack serialized message in str into this message instance 00374 @param str: byte array of serialized message 00375 @type str: str 00376 """ 00377 try: 00378 if self.action_goal is None: 00379 self.action_goal = pr2_create_object_model.msg.ModelObjectInHandActionGoal() 00380 if self.action_result is None: 00381 self.action_result = pr2_create_object_model.msg.ModelObjectInHandActionResult() 00382 if self.action_feedback is None: 00383 self.action_feedback = pr2_create_object_model.msg.ModelObjectInHandActionFeedback() 00384 end = 0 00385 _x = self 00386 start = end 00387 end += 12 00388 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00389 start = end 00390 end += 4 00391 (length,) = _struct_I.unpack(str[start:end]) 00392 start = end 00393 end += length 00394 self.action_goal.header.frame_id = str[start:end] 00395 _x = self 00396 start = end 00397 end += 8 00398 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00399 start = end 00400 end += 4 00401 (length,) = _struct_I.unpack(str[start:end]) 00402 start = end 00403 end += length 00404 self.action_goal.goal_id.id = 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.goal.arm_name = str[start:end] 00411 _x = self 00412 start = end 00413 end += 12 00414 (_x.action_goal.goal.clear_move.header.seq, _x.action_goal.goal.clear_move.header.stamp.secs, _x.action_goal.goal.clear_move.header.stamp.nsecs,) = _struct_3I.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.clear_move.header.frame_id = str[start:end] 00421 _x = self 00422 start = end 00423 end += 36 00424 (_x.action_goal.goal.clear_move.vector.x, _x.action_goal.goal.clear_move.vector.y, _x.action_goal.goal.clear_move.vector.z, _x.action_goal.goal.rotate_pose.header.seq, _x.action_goal.goal.rotate_pose.header.stamp.secs, _x.action_goal.goal.rotate_pose.header.stamp.nsecs,) = _struct_3d3I.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_goal.goal.rotate_pose.header.frame_id = str[start:end] 00431 _x = self 00432 start = end 00433 end += 71 00434 (_x.action_goal.goal.rotate_pose.pose.position.x, _x.action_goal.goal.rotate_pose.pose.position.y, _x.action_goal.goal.rotate_pose.pose.position.z, _x.action_goal.goal.rotate_pose.pose.orientation.x, _x.action_goal.goal.rotate_pose.pose.orientation.y, _x.action_goal.goal.rotate_pose.pose.orientation.z, _x.action_goal.goal.rotate_pose.pose.orientation.w, _x.action_goal.goal.rotate_object, _x.action_goal.goal.add_to_collision_map, _x.action_goal.goal.keep_level, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_7d3B3I.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.header.frame_id = str[start:end] 00441 _x = self 00442 start = end 00443 end += 8 00444 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00445 start = end 00446 end += 4 00447 (length,) = _struct_I.unpack(str[start:end]) 00448 start = end 00449 end += length 00450 self.action_result.status.goal_id.id = str[start:end] 00451 start = end 00452 end += 1 00453 (self.action_result.status.status,) = _struct_B.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_result.status.text = str[start:end] 00460 _x = self 00461 start = end 00462 end += 12 00463 (_x.action_result.result.cluster.header.seq, _x.action_result.result.cluster.header.stamp.secs, _x.action_result.result.cluster.header.stamp.nsecs,) = _struct_3I.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_result.result.cluster.header.frame_id = str[start:end] 00470 _x = self 00471 start = end 00472 end += 8 00473 (_x.action_result.result.cluster.height, _x.action_result.result.cluster.width,) = _struct_2I.unpack(str[start:end]) 00474 start = end 00475 end += 4 00476 (length,) = _struct_I.unpack(str[start:end]) 00477 self.action_result.result.cluster.fields = [] 00478 for i in range(0, length): 00479 val1 = sensor_msgs.msg.PointField() 00480 start = end 00481 end += 4 00482 (length,) = _struct_I.unpack(str[start:end]) 00483 start = end 00484 end += length 00485 val1.name = str[start:end] 00486 _x = val1 00487 start = end 00488 end += 9 00489 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 00490 self.action_result.result.cluster.fields.append(val1) 00491 _x = self 00492 start = end 00493 end += 9 00494 (_x.action_result.result.cluster.is_bigendian, _x.action_result.result.cluster.point_step, _x.action_result.result.cluster.row_step,) = _struct_B2I.unpack(str[start:end]) 00495 self.action_result.result.cluster.is_bigendian = bool(self.action_result.result.cluster.is_bigendian) 00496 start = end 00497 end += 4 00498 (length,) = _struct_I.unpack(str[start:end]) 00499 start = end 00500 end += length 00501 self.action_result.result.cluster.data = str[start:end] 00502 start = end 00503 end += 1 00504 (self.action_result.result.cluster.is_dense,) = _struct_B.unpack(str[start:end]) 00505 self.action_result.result.cluster.is_dense = bool(self.action_result.result.cluster.is_dense) 00506 start = end 00507 end += 4 00508 (length,) = _struct_I.unpack(str[start:end]) 00509 start = end 00510 end += length 00511 self.action_result.result.collision_name = str[start:end] 00512 _x = self 00513 start = end 00514 end += 12 00515 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.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_feedback.header.frame_id = str[start:end] 00522 _x = self 00523 start = end 00524 end += 8 00525 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.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.status.goal_id.id = str[start:end] 00532 start = end 00533 end += 1 00534 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00535 start = end 00536 end += 4 00537 (length,) = _struct_I.unpack(str[start:end]) 00538 start = end 00539 end += length 00540 self.action_feedback.status.text = str[start:end] 00541 _x = self 00542 start = end 00543 end += 8 00544 (_x.action_feedback.feedback.phase, _x.action_feedback.feedback.rotate_ind,) = _struct_2i.unpack(str[start:end]) 00545 return self 00546 except struct.error as e: 00547 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00548 00549 00550 def serialize_numpy(self, buff, numpy): 00551 """ 00552 serialize message with numpy array types into buffer 00553 @param buff: buffer 00554 @type buff: StringIO 00555 @param numpy: numpy python module 00556 @type numpy module 00557 """ 00558 try: 00559 _x = self 00560 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00561 _x = self.action_goal.header.frame_id 00562 length = len(_x) 00563 buff.write(struct.pack('<I%ss'%length, length, _x)) 00564 _x = self 00565 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00566 _x = self.action_goal.goal_id.id 00567 length = len(_x) 00568 buff.write(struct.pack('<I%ss'%length, length, _x)) 00569 _x = self.action_goal.goal.arm_name 00570 length = len(_x) 00571 buff.write(struct.pack('<I%ss'%length, length, _x)) 00572 _x = self 00573 buff.write(_struct_3I.pack(_x.action_goal.goal.clear_move.header.seq, _x.action_goal.goal.clear_move.header.stamp.secs, _x.action_goal.goal.clear_move.header.stamp.nsecs)) 00574 _x = self.action_goal.goal.clear_move.header.frame_id 00575 length = len(_x) 00576 buff.write(struct.pack('<I%ss'%length, length, _x)) 00577 _x = self 00578 buff.write(_struct_3d3I.pack(_x.action_goal.goal.clear_move.vector.x, _x.action_goal.goal.clear_move.vector.y, _x.action_goal.goal.clear_move.vector.z, _x.action_goal.goal.rotate_pose.header.seq, _x.action_goal.goal.rotate_pose.header.stamp.secs, _x.action_goal.goal.rotate_pose.header.stamp.nsecs)) 00579 _x = self.action_goal.goal.rotate_pose.header.frame_id 00580 length = len(_x) 00581 buff.write(struct.pack('<I%ss'%length, length, _x)) 00582 _x = self 00583 buff.write(_struct_7d3B3I.pack(_x.action_goal.goal.rotate_pose.pose.position.x, _x.action_goal.goal.rotate_pose.pose.position.y, _x.action_goal.goal.rotate_pose.pose.position.z, _x.action_goal.goal.rotate_pose.pose.orientation.x, _x.action_goal.goal.rotate_pose.pose.orientation.y, _x.action_goal.goal.rotate_pose.pose.orientation.z, _x.action_goal.goal.rotate_pose.pose.orientation.w, _x.action_goal.goal.rotate_object, _x.action_goal.goal.add_to_collision_map, _x.action_goal.goal.keep_level, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00584 _x = self.action_result.header.frame_id 00585 length = len(_x) 00586 buff.write(struct.pack('<I%ss'%length, length, _x)) 00587 _x = self 00588 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00589 _x = self.action_result.status.goal_id.id 00590 length = len(_x) 00591 buff.write(struct.pack('<I%ss'%length, length, _x)) 00592 buff.write(_struct_B.pack(self.action_result.status.status)) 00593 _x = self.action_result.status.text 00594 length = len(_x) 00595 buff.write(struct.pack('<I%ss'%length, length, _x)) 00596 _x = self 00597 buff.write(_struct_3I.pack(_x.action_result.result.cluster.header.seq, _x.action_result.result.cluster.header.stamp.secs, _x.action_result.result.cluster.header.stamp.nsecs)) 00598 _x = self.action_result.result.cluster.header.frame_id 00599 length = len(_x) 00600 buff.write(struct.pack('<I%ss'%length, length, _x)) 00601 _x = self 00602 buff.write(_struct_2I.pack(_x.action_result.result.cluster.height, _x.action_result.result.cluster.width)) 00603 length = len(self.action_result.result.cluster.fields) 00604 buff.write(_struct_I.pack(length)) 00605 for val1 in self.action_result.result.cluster.fields: 00606 _x = val1.name 00607 length = len(_x) 00608 buff.write(struct.pack('<I%ss'%length, length, _x)) 00609 _x = val1 00610 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 00611 _x = self 00612 buff.write(_struct_B2I.pack(_x.action_result.result.cluster.is_bigendian, _x.action_result.result.cluster.point_step, _x.action_result.result.cluster.row_step)) 00613 _x = self.action_result.result.cluster.data 00614 length = len(_x) 00615 # - if encoded as a list instead, serialize as bytes instead of string 00616 if type(_x) in [list, tuple]: 00617 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00618 else: 00619 buff.write(struct.pack('<I%ss'%length, length, _x)) 00620 buff.write(_struct_B.pack(self.action_result.result.cluster.is_dense)) 00621 _x = self.action_result.result.collision_name 00622 length = len(_x) 00623 buff.write(struct.pack('<I%ss'%length, length, _x)) 00624 _x = self 00625 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00626 _x = self.action_feedback.header.frame_id 00627 length = len(_x) 00628 buff.write(struct.pack('<I%ss'%length, length, _x)) 00629 _x = self 00630 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00631 _x = self.action_feedback.status.goal_id.id 00632 length = len(_x) 00633 buff.write(struct.pack('<I%ss'%length, length, _x)) 00634 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00635 _x = self.action_feedback.status.text 00636 length = len(_x) 00637 buff.write(struct.pack('<I%ss'%length, length, _x)) 00638 _x = self 00639 buff.write(_struct_2i.pack(_x.action_feedback.feedback.phase, _x.action_feedback.feedback.rotate_ind)) 00640 except struct.error as se: self._check_types(se) 00641 except TypeError as te: self._check_types(te) 00642 00643 def deserialize_numpy(self, str, numpy): 00644 """ 00645 unpack serialized message in str into this message instance using numpy for array types 00646 @param str: byte array of serialized message 00647 @type str: str 00648 @param numpy: numpy python module 00649 @type numpy: module 00650 """ 00651 try: 00652 if self.action_goal is None: 00653 self.action_goal = pr2_create_object_model.msg.ModelObjectInHandActionGoal() 00654 if self.action_result is None: 00655 self.action_result = pr2_create_object_model.msg.ModelObjectInHandActionResult() 00656 if self.action_feedback is None: 00657 self.action_feedback = pr2_create_object_model.msg.ModelObjectInHandActionFeedback() 00658 end = 0 00659 _x = self 00660 start = end 00661 end += 12 00662 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00663 start = end 00664 end += 4 00665 (length,) = _struct_I.unpack(str[start:end]) 00666 start = end 00667 end += length 00668 self.action_goal.header.frame_id = str[start:end] 00669 _x = self 00670 start = end 00671 end += 8 00672 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00673 start = end 00674 end += 4 00675 (length,) = _struct_I.unpack(str[start:end]) 00676 start = end 00677 end += length 00678 self.action_goal.goal_id.id = str[start:end] 00679 start = end 00680 end += 4 00681 (length,) = _struct_I.unpack(str[start:end]) 00682 start = end 00683 end += length 00684 self.action_goal.goal.arm_name = str[start:end] 00685 _x = self 00686 start = end 00687 end += 12 00688 (_x.action_goal.goal.clear_move.header.seq, _x.action_goal.goal.clear_move.header.stamp.secs, _x.action_goal.goal.clear_move.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00689 start = end 00690 end += 4 00691 (length,) = _struct_I.unpack(str[start:end]) 00692 start = end 00693 end += length 00694 self.action_goal.goal.clear_move.header.frame_id = str[start:end] 00695 _x = self 00696 start = end 00697 end += 36 00698 (_x.action_goal.goal.clear_move.vector.x, _x.action_goal.goal.clear_move.vector.y, _x.action_goal.goal.clear_move.vector.z, _x.action_goal.goal.rotate_pose.header.seq, _x.action_goal.goal.rotate_pose.header.stamp.secs, _x.action_goal.goal.rotate_pose.header.stamp.nsecs,) = _struct_3d3I.unpack(str[start:end]) 00699 start = end 00700 end += 4 00701 (length,) = _struct_I.unpack(str[start:end]) 00702 start = end 00703 end += length 00704 self.action_goal.goal.rotate_pose.header.frame_id = str[start:end] 00705 _x = self 00706 start = end 00707 end += 71 00708 (_x.action_goal.goal.rotate_pose.pose.position.x, _x.action_goal.goal.rotate_pose.pose.position.y, _x.action_goal.goal.rotate_pose.pose.position.z, _x.action_goal.goal.rotate_pose.pose.orientation.x, _x.action_goal.goal.rotate_pose.pose.orientation.y, _x.action_goal.goal.rotate_pose.pose.orientation.z, _x.action_goal.goal.rotate_pose.pose.orientation.w, _x.action_goal.goal.rotate_object, _x.action_goal.goal.add_to_collision_map, _x.action_goal.goal.keep_level, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_7d3B3I.unpack(str[start:end]) 00709 start = end 00710 end += 4 00711 (length,) = _struct_I.unpack(str[start:end]) 00712 start = end 00713 end += length 00714 self.action_result.header.frame_id = str[start:end] 00715 _x = self 00716 start = end 00717 end += 8 00718 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00719 start = end 00720 end += 4 00721 (length,) = _struct_I.unpack(str[start:end]) 00722 start = end 00723 end += length 00724 self.action_result.status.goal_id.id = str[start:end] 00725 start = end 00726 end += 1 00727 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 00728 start = end 00729 end += 4 00730 (length,) = _struct_I.unpack(str[start:end]) 00731 start = end 00732 end += length 00733 self.action_result.status.text = str[start:end] 00734 _x = self 00735 start = end 00736 end += 12 00737 (_x.action_result.result.cluster.header.seq, _x.action_result.result.cluster.header.stamp.secs, _x.action_result.result.cluster.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00738 start = end 00739 end += 4 00740 (length,) = _struct_I.unpack(str[start:end]) 00741 start = end 00742 end += length 00743 self.action_result.result.cluster.header.frame_id = str[start:end] 00744 _x = self 00745 start = end 00746 end += 8 00747 (_x.action_result.result.cluster.height, _x.action_result.result.cluster.width,) = _struct_2I.unpack(str[start:end]) 00748 start = end 00749 end += 4 00750 (length,) = _struct_I.unpack(str[start:end]) 00751 self.action_result.result.cluster.fields = [] 00752 for i in range(0, length): 00753 val1 = sensor_msgs.msg.PointField() 00754 start = end 00755 end += 4 00756 (length,) = _struct_I.unpack(str[start:end]) 00757 start = end 00758 end += length 00759 val1.name = str[start:end] 00760 _x = val1 00761 start = end 00762 end += 9 00763 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 00764 self.action_result.result.cluster.fields.append(val1) 00765 _x = self 00766 start = end 00767 end += 9 00768 (_x.action_result.result.cluster.is_bigendian, _x.action_result.result.cluster.point_step, _x.action_result.result.cluster.row_step,) = _struct_B2I.unpack(str[start:end]) 00769 self.action_result.result.cluster.is_bigendian = bool(self.action_result.result.cluster.is_bigendian) 00770 start = end 00771 end += 4 00772 (length,) = _struct_I.unpack(str[start:end]) 00773 start = end 00774 end += length 00775 self.action_result.result.cluster.data = str[start:end] 00776 start = end 00777 end += 1 00778 (self.action_result.result.cluster.is_dense,) = _struct_B.unpack(str[start:end]) 00779 self.action_result.result.cluster.is_dense = bool(self.action_result.result.cluster.is_dense) 00780 start = end 00781 end += 4 00782 (length,) = _struct_I.unpack(str[start:end]) 00783 start = end 00784 end += length 00785 self.action_result.result.collision_name = str[start:end] 00786 _x = self 00787 start = end 00788 end += 12 00789 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00790 start = end 00791 end += 4 00792 (length,) = _struct_I.unpack(str[start:end]) 00793 start = end 00794 end += length 00795 self.action_feedback.header.frame_id = str[start:end] 00796 _x = self 00797 start = end 00798 end += 8 00799 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00800 start = end 00801 end += 4 00802 (length,) = _struct_I.unpack(str[start:end]) 00803 start = end 00804 end += length 00805 self.action_feedback.status.goal_id.id = str[start:end] 00806 start = end 00807 end += 1 00808 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 00809 start = end 00810 end += 4 00811 (length,) = _struct_I.unpack(str[start:end]) 00812 start = end 00813 end += length 00814 self.action_feedback.status.text = str[start:end] 00815 _x = self 00816 start = end 00817 end += 8 00818 (_x.action_feedback.feedback.phase, _x.action_feedback.feedback.rotate_ind,) = _struct_2i.unpack(str[start:end]) 00819 return self 00820 except struct.error as e: 00821 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00822 00823 _struct_I = roslib.message.struct_I 00824 _struct_7d3B3I = struct.Struct("<7d3B3I") 00825 _struct_3d3I = struct.Struct("<3d3I") 00826 _struct_B = struct.Struct("<B") 00827 _struct_IBI = struct.Struct("<IBI") 00828 _struct_2i = struct.Struct("<2i") 00829 _struct_3I = struct.Struct("<3I") 00830 _struct_B2I = struct.Struct("<B2I") 00831 _struct_2I = struct.Struct("<2I")