$search
00001 """autogenerated by genmsg_py from GraspHandPostureExecutionAction.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import object_manipulation_msgs.msg 00006 import roslib.rostime 00007 import actionlib_msgs.msg 00008 import geometry_msgs.msg 00009 import sensor_msgs.msg 00010 import household_objects_database_msgs.msg 00011 import std_msgs.msg 00012 00013 class GraspHandPostureExecutionAction(roslib.message.Message): 00014 _md5sum = "9c7b002a44b8ec73513d411e2f3befd4" 00015 _type = "object_manipulation_msgs/GraspHandPostureExecutionAction" 00016 _has_header = False #flag to mark the presence of a Header object 00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00018 00019 GraspHandPostureExecutionActionGoal action_goal 00020 GraspHandPostureExecutionActionResult action_result 00021 GraspHandPostureExecutionActionFeedback action_feedback 00022 00023 ================================================================================ 00024 MSG: object_manipulation_msgs/GraspHandPostureExecutionActionGoal 00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00026 00027 Header header 00028 actionlib_msgs/GoalID goal_id 00029 GraspHandPostureExecutionGoal goal 00030 00031 ================================================================================ 00032 MSG: std_msgs/Header 00033 # Standard metadata for higher-level stamped data types. 00034 # This is generally used to communicate timestamped data 00035 # in a particular coordinate frame. 00036 # 00037 # sequence ID: consecutively increasing ID 00038 uint32 seq 00039 #Two-integer timestamp that is expressed as: 00040 # * stamp.secs: seconds (stamp_secs) since epoch 00041 # * stamp.nsecs: nanoseconds since stamp_secs 00042 # time-handling sugar is provided by the client library 00043 time stamp 00044 #Frame this data is associated with 00045 # 0: no frame 00046 # 1: global frame 00047 string frame_id 00048 00049 ================================================================================ 00050 MSG: actionlib_msgs/GoalID 00051 # The stamp should store the time at which this goal was requested. 00052 # It is used by an action server when it tries to preempt all 00053 # goals that were requested before a certain time 00054 time stamp 00055 00056 # The id provides a way to associate feedback and 00057 # result message with specific goal requests. The id 00058 # specified must be unique. 00059 string id 00060 00061 00062 ================================================================================ 00063 MSG: object_manipulation_msgs/GraspHandPostureExecutionGoal 00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00065 # an action for requesting the finger posture part of grasp be physically carried out by a hand 00066 # the name of the arm being used is not in here, as this will be sent to a specific action server 00067 # for each arm 00068 00069 # the grasp to be executed 00070 Grasp grasp 00071 00072 # the goal of this action 00073 # requests that the hand be set in the pre-grasp posture 00074 int32 PRE_GRASP=1 00075 # requests that the hand execute the actual grasp 00076 int32 GRASP=2 00077 # requests that the hand open to release the object 00078 int32 RELEASE=3 00079 int32 goal 00080 00081 # the max contact force to use (<=0 if no desired max) 00082 float32 max_contact_force 00083 00084 00085 ================================================================================ 00086 MSG: object_manipulation_msgs/Grasp 00087 00088 # The internal posture of the hand for the pre-grasp 00089 # only positions are used 00090 sensor_msgs/JointState pre_grasp_posture 00091 00092 # The internal posture of the hand for the grasp 00093 # positions and efforts are used 00094 sensor_msgs/JointState grasp_posture 00095 00096 # The position of the end-effector for the grasp relative to a reference frame 00097 # (that is always specified elsewhere, not in this message) 00098 geometry_msgs/Pose grasp_pose 00099 00100 # The estimated probability of success for this grasp 00101 float64 success_probability 00102 00103 # Debug flag to indicate that this grasp would be the best in its cluster 00104 bool cluster_rep 00105 00106 # how far the pre-grasp should ideally be away from the grasp 00107 float32 desired_approach_distance 00108 00109 # how much distance between pre-grasp and grasp must actually be feasible 00110 # for the grasp not to be rejected 00111 float32 min_approach_distance 00112 00113 # an optional list of obstacles that we have semantic information about 00114 # and that we expect might move in the course of executing this grasp 00115 # the grasp planner is expected to make sure they move in an OK way; during 00116 # execution, grasp executors will not check for collisions against these objects 00117 GraspableObject[] moved_obstacles 00118 00119 ================================================================================ 00120 MSG: sensor_msgs/JointState 00121 # This is a message that holds data to describe the state of a set of torque controlled joints. 00122 # 00123 # The state of each joint (revolute or prismatic) is defined by: 00124 # * the position of the joint (rad or m), 00125 # * the velocity of the joint (rad/s or m/s) and 00126 # * the effort that is applied in the joint (Nm or N). 00127 # 00128 # Each joint is uniquely identified by its name 00129 # The header specifies the time at which the joint states were recorded. All the joint states 00130 # in one message have to be recorded at the same time. 00131 # 00132 # This message consists of a multiple arrays, one for each part of the joint state. 00133 # The goal is to make each of the fields optional. When e.g. your joints have no 00134 # effort associated with them, you can leave the effort array empty. 00135 # 00136 # All arrays in this message should have the same size, or be empty. 00137 # This is the only way to uniquely associate the joint name with the correct 00138 # states. 00139 00140 00141 Header header 00142 00143 string[] name 00144 float64[] position 00145 float64[] velocity 00146 float64[] effort 00147 00148 ================================================================================ 00149 MSG: geometry_msgs/Pose 00150 # A representation of pose in free space, composed of postion and orientation. 00151 Point position 00152 Quaternion orientation 00153 00154 ================================================================================ 00155 MSG: geometry_msgs/Point 00156 # This contains the position of a point in free space 00157 float64 x 00158 float64 y 00159 float64 z 00160 00161 ================================================================================ 00162 MSG: geometry_msgs/Quaternion 00163 # This represents an orientation in free space in quaternion form. 00164 00165 float64 x 00166 float64 y 00167 float64 z 00168 float64 w 00169 00170 ================================================================================ 00171 MSG: object_manipulation_msgs/GraspableObject 00172 # an object that the object_manipulator can work on 00173 00174 # a graspable object can be represented in multiple ways. This message 00175 # can contain all of them. Which one is actually used is up to the receiver 00176 # of this message. When adding new representations, one must be careful that 00177 # they have reasonable lightweight defaults indicating that that particular 00178 # representation is not available. 00179 00180 # the tf frame to be used as a reference frame when combining information from 00181 # the different representations below 00182 string reference_frame_id 00183 00184 # potential recognition results from a database of models 00185 # all poses are relative to the object reference pose 00186 household_objects_database_msgs/DatabaseModelPose[] potential_models 00187 00188 # the point cloud itself 00189 sensor_msgs/PointCloud cluster 00190 00191 # a region of a PointCloud2 of interest 00192 object_manipulation_msgs/SceneRegion region 00193 00194 # the name that this object has in the collision environment 00195 string collision_name 00196 ================================================================================ 00197 MSG: household_objects_database_msgs/DatabaseModelPose 00198 # Informs that a specific model from the Model Database has been 00199 # identified at a certain location 00200 00201 # the database id of the model 00202 int32 model_id 00203 00204 # the pose that it can be found in 00205 geometry_msgs/PoseStamped pose 00206 00207 # a measure of the confidence level in this detection result 00208 float32 confidence 00209 00210 # the name of the object detector that generated this detection result 00211 string detector_name 00212 00213 ================================================================================ 00214 MSG: geometry_msgs/PoseStamped 00215 # A Pose with reference coordinate frame and timestamp 00216 Header header 00217 Pose pose 00218 00219 ================================================================================ 00220 MSG: sensor_msgs/PointCloud 00221 # This message holds a collection of 3d points, plus optional additional 00222 # information about each point. 00223 00224 # Time of sensor data acquisition, coordinate frame ID. 00225 Header header 00226 00227 # Array of 3d points. Each Point32 should be interpreted as a 3d point 00228 # in the frame given in the header. 00229 geometry_msgs/Point32[] points 00230 00231 # Each channel should have the same number of elements as points array, 00232 # and the data in each channel should correspond 1:1 with each point. 00233 # Channel names in common practice are listed in ChannelFloat32.msg. 00234 ChannelFloat32[] channels 00235 00236 ================================================================================ 00237 MSG: geometry_msgs/Point32 00238 # This contains the position of a point in free space(with 32 bits of precision). 00239 # It is recommeded to use Point wherever possible instead of Point32. 00240 # 00241 # This recommendation is to promote interoperability. 00242 # 00243 # This message is designed to take up less space when sending 00244 # lots of points at once, as in the case of a PointCloud. 00245 00246 float32 x 00247 float32 y 00248 float32 z 00249 ================================================================================ 00250 MSG: sensor_msgs/ChannelFloat32 00251 # This message is used by the PointCloud message to hold optional data 00252 # associated with each point in the cloud. The length of the values 00253 # array should be the same as the length of the points array in the 00254 # PointCloud, and each value should be associated with the corresponding 00255 # point. 00256 00257 # Channel names in existing practice include: 00258 # "u", "v" - row and column (respectively) in the left stereo image. 00259 # This is opposite to usual conventions but remains for 00260 # historical reasons. The newer PointCloud2 message has no 00261 # such problem. 00262 # "rgb" - For point clouds produced by color stereo cameras. uint8 00263 # (R,G,B) values packed into the least significant 24 bits, 00264 # in order. 00265 # "intensity" - laser or pixel intensity. 00266 # "distance" 00267 00268 # The channel name should give semantics of the channel (e.g. 00269 # "intensity" instead of "value"). 00270 string name 00271 00272 # The values array should be 1-1 with the elements of the associated 00273 # PointCloud. 00274 float32[] values 00275 00276 ================================================================================ 00277 MSG: object_manipulation_msgs/SceneRegion 00278 # Point cloud 00279 sensor_msgs/PointCloud2 cloud 00280 00281 # Indices for the region of interest 00282 int32[] mask 00283 00284 # One of the corresponding 2D images, if applicable 00285 sensor_msgs/Image image 00286 00287 # The disparity image, if applicable 00288 sensor_msgs/Image disparity_image 00289 00290 # Camera info for the camera that took the image 00291 sensor_msgs/CameraInfo cam_info 00292 00293 # a 3D region of interest for grasp planning 00294 geometry_msgs/PoseStamped roi_box_pose 00295 geometry_msgs/Vector3 roi_box_dims 00296 00297 ================================================================================ 00298 MSG: sensor_msgs/PointCloud2 00299 # This message holds a collection of N-dimensional points, which may 00300 # contain additional information such as normals, intensity, etc. The 00301 # point data is stored as a binary blob, its layout described by the 00302 # contents of the "fields" array. 00303 00304 # The point cloud data may be organized 2d (image-like) or 1d 00305 # (unordered). Point clouds organized as 2d images may be produced by 00306 # camera depth sensors such as stereo or time-of-flight. 00307 00308 # Time of sensor data acquisition, and the coordinate frame ID (for 3d 00309 # points). 00310 Header header 00311 00312 # 2D structure of the point cloud. If the cloud is unordered, height is 00313 # 1 and width is the length of the point cloud. 00314 uint32 height 00315 uint32 width 00316 00317 # Describes the channels and their layout in the binary data blob. 00318 PointField[] fields 00319 00320 bool is_bigendian # Is this data bigendian? 00321 uint32 point_step # Length of a point in bytes 00322 uint32 row_step # Length of a row in bytes 00323 uint8[] data # Actual point data, size is (row_step*height) 00324 00325 bool is_dense # True if there are no invalid points 00326 00327 ================================================================================ 00328 MSG: sensor_msgs/PointField 00329 # This message holds the description of one point entry in the 00330 # PointCloud2 message format. 00331 uint8 INT8 = 1 00332 uint8 UINT8 = 2 00333 uint8 INT16 = 3 00334 uint8 UINT16 = 4 00335 uint8 INT32 = 5 00336 uint8 UINT32 = 6 00337 uint8 FLOAT32 = 7 00338 uint8 FLOAT64 = 8 00339 00340 string name # Name of field 00341 uint32 offset # Offset from start of point struct 00342 uint8 datatype # Datatype enumeration, see above 00343 uint32 count # How many elements in the field 00344 00345 ================================================================================ 00346 MSG: sensor_msgs/Image 00347 # This message contains an uncompressed image 00348 # (0, 0) is at top-left corner of image 00349 # 00350 00351 Header header # Header timestamp should be acquisition time of image 00352 # Header frame_id should be optical frame of camera 00353 # origin of frame should be optical center of cameara 00354 # +x should point to the right in the image 00355 # +y should point down in the image 00356 # +z should point into to plane of the image 00357 # If the frame_id here and the frame_id of the CameraInfo 00358 # message associated with the image conflict 00359 # the behavior is undefined 00360 00361 uint32 height # image height, that is, number of rows 00362 uint32 width # image width, that is, number of columns 00363 00364 # The legal values for encoding are in file src/image_encodings.cpp 00365 # If you want to standardize a new string format, join 00366 # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 00367 00368 string encoding # Encoding of pixels -- channel meaning, ordering, size 00369 # taken from the list of strings in src/image_encodings.cpp 00370 00371 uint8 is_bigendian # is this data bigendian? 00372 uint32 step # Full row length in bytes 00373 uint8[] data # actual matrix data, size is (step * rows) 00374 00375 ================================================================================ 00376 MSG: sensor_msgs/CameraInfo 00377 # This message defines meta information for a camera. It should be in a 00378 # camera namespace on topic "camera_info" and accompanied by up to five 00379 # image topics named: 00380 # 00381 # image_raw - raw data from the camera driver, possibly Bayer encoded 00382 # image - monochrome, distorted 00383 # image_color - color, distorted 00384 # image_rect - monochrome, rectified 00385 # image_rect_color - color, rectified 00386 # 00387 # The image_pipeline contains packages (image_proc, stereo_image_proc) 00388 # for producing the four processed image topics from image_raw and 00389 # camera_info. The meaning of the camera parameters are described in 00390 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. 00391 # 00392 # The image_geometry package provides a user-friendly interface to 00393 # common operations using this meta information. If you want to, e.g., 00394 # project a 3d point into image coordinates, we strongly recommend 00395 # using image_geometry. 00396 # 00397 # If the camera is uncalibrated, the matrices D, K, R, P should be left 00398 # zeroed out. In particular, clients may assume that K[0] == 0.0 00399 # indicates an uncalibrated camera. 00400 00401 ####################################################################### 00402 # Image acquisition info # 00403 ####################################################################### 00404 00405 # Time of image acquisition, camera coordinate frame ID 00406 Header header # Header timestamp should be acquisition time of image 00407 # Header frame_id should be optical frame of camera 00408 # origin of frame should be optical center of camera 00409 # +x should point to the right in the image 00410 # +y should point down in the image 00411 # +z should point into the plane of the image 00412 00413 00414 ####################################################################### 00415 # Calibration Parameters # 00416 ####################################################################### 00417 # These are fixed during camera calibration. Their values will be the # 00418 # same in all messages until the camera is recalibrated. Note that # 00419 # self-calibrating systems may "recalibrate" frequently. # 00420 # # 00421 # The internal parameters can be used to warp a raw (distorted) image # 00422 # to: # 00423 # 1. An undistorted image (requires D and K) # 00424 # 2. A rectified image (requires D, K, R) # 00425 # The projection matrix P projects 3D points into the rectified image.# 00426 ####################################################################### 00427 00428 # The image dimensions with which the camera was calibrated. Normally 00429 # this will be the full camera resolution in pixels. 00430 uint32 height 00431 uint32 width 00432 00433 # The distortion model used. Supported models are listed in 00434 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a 00435 # simple model of radial and tangential distortion - is sufficent. 00436 string distortion_model 00437 00438 # The distortion parameters, size depending on the distortion model. 00439 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). 00440 float64[] D 00441 00442 # Intrinsic camera matrix for the raw (distorted) images. 00443 # [fx 0 cx] 00444 # K = [ 0 fy cy] 00445 # [ 0 0 1] 00446 # Projects 3D points in the camera coordinate frame to 2D pixel 00447 # coordinates using the focal lengths (fx, fy) and principal point 00448 # (cx, cy). 00449 float64[9] K # 3x3 row-major matrix 00450 00451 # Rectification matrix (stereo cameras only) 00452 # A rotation matrix aligning the camera coordinate system to the ideal 00453 # stereo image plane so that epipolar lines in both stereo images are 00454 # parallel. 00455 float64[9] R # 3x3 row-major matrix 00456 00457 # Projection/camera matrix 00458 # [fx' 0 cx' Tx] 00459 # P = [ 0 fy' cy' Ty] 00460 # [ 0 0 1 0] 00461 # By convention, this matrix specifies the intrinsic (camera) matrix 00462 # of the processed (rectified) image. That is, the left 3x3 portion 00463 # is the normal camera intrinsic matrix for the rectified image. 00464 # It projects 3D points in the camera coordinate frame to 2D pixel 00465 # coordinates using the focal lengths (fx', fy') and principal point 00466 # (cx', cy') - these may differ from the values in K. 00467 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will 00468 # also have R = the identity and P[1:3,1:3] = K. 00469 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the 00470 # position of the optical center of the second camera in the first 00471 # camera's frame. We assume Tz = 0 so both cameras are in the same 00472 # stereo image plane. The first camera always has Tx = Ty = 0. For 00473 # the right (second) camera of a horizontal stereo pair, Ty = 0 and 00474 # Tx = -fx' * B, where B is the baseline between the cameras. 00475 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto 00476 # the rectified image is given by: 00477 # [u v w]' = P * [X Y Z 1]' 00478 # x = u / w 00479 # y = v / w 00480 # This holds for both images of a stereo pair. 00481 float64[12] P # 3x4 row-major matrix 00482 00483 00484 ####################################################################### 00485 # Operational Parameters # 00486 ####################################################################### 00487 # These define the image region actually captured by the camera # 00488 # driver. Although they affect the geometry of the output image, they # 00489 # may be changed freely without recalibrating the camera. # 00490 ####################################################################### 00491 00492 # Binning refers here to any camera setting which combines rectangular 00493 # neighborhoods of pixels into larger "super-pixels." It reduces the 00494 # resolution of the output image to 00495 # (width / binning_x) x (height / binning_y). 00496 # The default values binning_x = binning_y = 0 is considered the same 00497 # as binning_x = binning_y = 1 (no subsampling). 00498 uint32 binning_x 00499 uint32 binning_y 00500 00501 # Region of interest (subwindow of full camera resolution), given in 00502 # full resolution (unbinned) image coordinates. A particular ROI 00503 # always denotes the same window of pixels on the camera sensor, 00504 # regardless of binning settings. 00505 # The default setting of roi (all values 0) is considered the same as 00506 # full resolution (roi.width = width, roi.height = height). 00507 RegionOfInterest roi 00508 00509 ================================================================================ 00510 MSG: sensor_msgs/RegionOfInterest 00511 # This message is used to specify a region of interest within an image. 00512 # 00513 # When used to specify the ROI setting of the camera when the image was 00514 # taken, the height and width fields should either match the height and 00515 # width fields for the associated image; or height = width = 0 00516 # indicates that the full resolution image was captured. 00517 00518 uint32 x_offset # Leftmost pixel of the ROI 00519 # (0 if the ROI includes the left edge of the image) 00520 uint32 y_offset # Topmost pixel of the ROI 00521 # (0 if the ROI includes the top edge of the image) 00522 uint32 height # Height of ROI 00523 uint32 width # Width of ROI 00524 00525 # True if a distinct rectified ROI should be calculated from the "raw" 00526 # ROI in this message. Typically this should be False if the full image 00527 # is captured (ROI not used), and True if a subwindow is captured (ROI 00528 # used). 00529 bool do_rectify 00530 00531 ================================================================================ 00532 MSG: geometry_msgs/Vector3 00533 # This represents a vector in free space. 00534 00535 float64 x 00536 float64 y 00537 float64 z 00538 ================================================================================ 00539 MSG: object_manipulation_msgs/GraspHandPostureExecutionActionResult 00540 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00541 00542 Header header 00543 actionlib_msgs/GoalStatus status 00544 GraspHandPostureExecutionResult result 00545 00546 ================================================================================ 00547 MSG: actionlib_msgs/GoalStatus 00548 GoalID goal_id 00549 uint8 status 00550 uint8 PENDING = 0 # The goal has yet to be processed by the action server 00551 uint8 ACTIVE = 1 # The goal is currently being processed by the action server 00552 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 00553 # and has since completed its execution (Terminal State) 00554 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 00555 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 00556 # to some failure (Terminal State) 00557 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 00558 # because the goal was unattainable or invalid (Terminal State) 00559 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 00560 # and has not yet completed execution 00561 uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 00562 # but the action server has not yet confirmed that the goal is canceled 00563 uint8 RECALLED = 8 # The goal received a cancel request before it started executing 00564 # and was successfully cancelled (Terminal State) 00565 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 00566 # sent over the wire by an action server 00567 00568 #Allow for the user to associate a string with GoalStatus for debugging 00569 string text 00570 00571 00572 ================================================================================ 00573 MSG: object_manipulation_msgs/GraspHandPostureExecutionResult 00574 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00575 # the result of the action 00576 ManipulationResult result 00577 00578 00579 ================================================================================ 00580 MSG: object_manipulation_msgs/ManipulationResult 00581 # Result codes for manipulation tasks 00582 00583 # task completed as expected 00584 # generally means you can proceed as planned 00585 int32 SUCCESS = 1 00586 00587 # task not possible (e.g. out of reach or obstacles in the way) 00588 # generally means that the world was not disturbed, so you can try another task 00589 int32 UNFEASIBLE = -1 00590 00591 # task was thought possible, but failed due to unexpected events during execution 00592 # it is likely that the world was disturbed, so you are encouraged to refresh 00593 # your sensed world model before proceeding to another task 00594 int32 FAILED = -2 00595 00596 # a lower level error prevented task completion (e.g. joint controller not responding) 00597 # generally requires human attention 00598 int32 ERROR = -3 00599 00600 # means that at some point during execution we ended up in a state that the collision-aware 00601 # arm navigation module will not move out of. The world was likely not disturbed, but you 00602 # probably need a new collision map to move the arm out of the stuck position 00603 int32 ARM_MOVEMENT_PREVENTED = -4 00604 00605 # specific to grasp actions 00606 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested 00607 # it is likely that the collision environment will see collisions between the hand/object and the support surface 00608 int32 LIFT_FAILED = -5 00609 00610 # specific to place actions 00611 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested 00612 # it is likely that the collision environment will see collisions between the hand and the object 00613 int32 RETREAT_FAILED = -6 00614 00615 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else" 00616 int32 CANCELLED = -7 00617 00618 # the actual value of this error code 00619 int32 value 00620 00621 ================================================================================ 00622 MSG: object_manipulation_msgs/GraspHandPostureExecutionActionFeedback 00623 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00624 00625 Header header 00626 actionlib_msgs/GoalStatus status 00627 GraspHandPostureExecutionFeedback feedback 00628 00629 ================================================================================ 00630 MSG: object_manipulation_msgs/GraspHandPostureExecutionFeedback 00631 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00632 # empty for now 00633 00634 00635 00636 """ 00637 __slots__ = ['action_goal','action_result','action_feedback'] 00638 _slot_types = ['object_manipulation_msgs/GraspHandPostureExecutionActionGoal','object_manipulation_msgs/GraspHandPostureExecutionActionResult','object_manipulation_msgs/GraspHandPostureExecutionActionFeedback'] 00639 00640 def __init__(self, *args, **kwds): 00641 """ 00642 Constructor. Any message fields that are implicitly/explicitly 00643 set to None will be assigned a default value. The recommend 00644 use is keyword arguments as this is more robust to future message 00645 changes. You cannot mix in-order arguments and keyword arguments. 00646 00647 The available fields are: 00648 action_goal,action_result,action_feedback 00649 00650 @param args: complete set of field values, in .msg order 00651 @param kwds: use keyword arguments corresponding to message field names 00652 to set specific fields. 00653 """ 00654 if args or kwds: 00655 super(GraspHandPostureExecutionAction, self).__init__(*args, **kwds) 00656 #message fields cannot be None, assign default values for those that are 00657 if self.action_goal is None: 00658 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal() 00659 if self.action_result is None: 00660 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult() 00661 if self.action_feedback is None: 00662 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback() 00663 else: 00664 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal() 00665 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult() 00666 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback() 00667 00668 def _get_types(self): 00669 """ 00670 internal API method 00671 """ 00672 return self._slot_types 00673 00674 def serialize(self, buff): 00675 """ 00676 serialize message into buffer 00677 @param buff: buffer 00678 @type buff: StringIO 00679 """ 00680 try: 00681 _x = self 00682 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 00683 _x = self.action_goal.header.frame_id 00684 length = len(_x) 00685 buff.write(struct.pack('<I%ss'%length, length, _x)) 00686 _x = self 00687 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 00688 _x = self.action_goal.goal_id.id 00689 length = len(_x) 00690 buff.write(struct.pack('<I%ss'%length, length, _x)) 00691 _x = self 00692 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs)) 00693 _x = self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id 00694 length = len(_x) 00695 buff.write(struct.pack('<I%ss'%length, length, _x)) 00696 length = len(self.action_goal.goal.grasp.pre_grasp_posture.name) 00697 buff.write(_struct_I.pack(length)) 00698 for val1 in self.action_goal.goal.grasp.pre_grasp_posture.name: 00699 length = len(val1) 00700 buff.write(struct.pack('<I%ss'%length, length, val1)) 00701 length = len(self.action_goal.goal.grasp.pre_grasp_posture.position) 00702 buff.write(_struct_I.pack(length)) 00703 pattern = '<%sd'%length 00704 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.pre_grasp_posture.position)) 00705 length = len(self.action_goal.goal.grasp.pre_grasp_posture.velocity) 00706 buff.write(_struct_I.pack(length)) 00707 pattern = '<%sd'%length 00708 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.pre_grasp_posture.velocity)) 00709 length = len(self.action_goal.goal.grasp.pre_grasp_posture.effort) 00710 buff.write(_struct_I.pack(length)) 00711 pattern = '<%sd'%length 00712 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.pre_grasp_posture.effort)) 00713 _x = self 00714 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs)) 00715 _x = self.action_goal.goal.grasp.grasp_posture.header.frame_id 00716 length = len(_x) 00717 buff.write(struct.pack('<I%ss'%length, length, _x)) 00718 length = len(self.action_goal.goal.grasp.grasp_posture.name) 00719 buff.write(_struct_I.pack(length)) 00720 for val1 in self.action_goal.goal.grasp.grasp_posture.name: 00721 length = len(val1) 00722 buff.write(struct.pack('<I%ss'%length, length, val1)) 00723 length = len(self.action_goal.goal.grasp.grasp_posture.position) 00724 buff.write(_struct_I.pack(length)) 00725 pattern = '<%sd'%length 00726 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.grasp_posture.position)) 00727 length = len(self.action_goal.goal.grasp.grasp_posture.velocity) 00728 buff.write(_struct_I.pack(length)) 00729 pattern = '<%sd'%length 00730 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.grasp_posture.velocity)) 00731 length = len(self.action_goal.goal.grasp.grasp_posture.effort) 00732 buff.write(_struct_I.pack(length)) 00733 pattern = '<%sd'%length 00734 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.grasp_posture.effort)) 00735 _x = self 00736 buff.write(_struct_8dB2f.pack(_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.grasp.desired_approach_distance, _x.action_goal.goal.grasp.min_approach_distance)) 00737 length = len(self.action_goal.goal.grasp.moved_obstacles) 00738 buff.write(_struct_I.pack(length)) 00739 for val1 in self.action_goal.goal.grasp.moved_obstacles: 00740 _x = val1.reference_frame_id 00741 length = len(_x) 00742 buff.write(struct.pack('<I%ss'%length, length, _x)) 00743 length = len(val1.potential_models) 00744 buff.write(_struct_I.pack(length)) 00745 for val2 in val1.potential_models: 00746 buff.write(_struct_i.pack(val2.model_id)) 00747 _v1 = val2.pose 00748 _v2 = _v1.header 00749 buff.write(_struct_I.pack(_v2.seq)) 00750 _v3 = _v2.stamp 00751 _x = _v3 00752 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00753 _x = _v2.frame_id 00754 length = len(_x) 00755 buff.write(struct.pack('<I%ss'%length, length, _x)) 00756 _v4 = _v1.pose 00757 _v5 = _v4.position 00758 _x = _v5 00759 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00760 _v6 = _v4.orientation 00761 _x = _v6 00762 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00763 buff.write(_struct_f.pack(val2.confidence)) 00764 _x = val2.detector_name 00765 length = len(_x) 00766 buff.write(struct.pack('<I%ss'%length, length, _x)) 00767 _v7 = val1.cluster 00768 _v8 = _v7.header 00769 buff.write(_struct_I.pack(_v8.seq)) 00770 _v9 = _v8.stamp 00771 _x = _v9 00772 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00773 _x = _v8.frame_id 00774 length = len(_x) 00775 buff.write(struct.pack('<I%ss'%length, length, _x)) 00776 length = len(_v7.points) 00777 buff.write(_struct_I.pack(length)) 00778 for val3 in _v7.points: 00779 _x = val3 00780 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00781 length = len(_v7.channels) 00782 buff.write(_struct_I.pack(length)) 00783 for val3 in _v7.channels: 00784 _x = val3.name 00785 length = len(_x) 00786 buff.write(struct.pack('<I%ss'%length, length, _x)) 00787 length = len(val3.values) 00788 buff.write(_struct_I.pack(length)) 00789 pattern = '<%sf'%length 00790 buff.write(struct.pack(pattern, *val3.values)) 00791 _v10 = val1.region 00792 _v11 = _v10.cloud 00793 _v12 = _v11.header 00794 buff.write(_struct_I.pack(_v12.seq)) 00795 _v13 = _v12.stamp 00796 _x = _v13 00797 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00798 _x = _v12.frame_id 00799 length = len(_x) 00800 buff.write(struct.pack('<I%ss'%length, length, _x)) 00801 _x = _v11 00802 buff.write(_struct_2I.pack(_x.height, _x.width)) 00803 length = len(_v11.fields) 00804 buff.write(_struct_I.pack(length)) 00805 for val4 in _v11.fields: 00806 _x = val4.name 00807 length = len(_x) 00808 buff.write(struct.pack('<I%ss'%length, length, _x)) 00809 _x = val4 00810 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 00811 _x = _v11 00812 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step)) 00813 _x = _v11.data 00814 length = len(_x) 00815 # - if encoded as a list instead, serialize as bytes instead of string 00816 if type(_x) in [list, tuple]: 00817 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00818 else: 00819 buff.write(struct.pack('<I%ss'%length, length, _x)) 00820 buff.write(_struct_B.pack(_v11.is_dense)) 00821 length = len(_v10.mask) 00822 buff.write(_struct_I.pack(length)) 00823 pattern = '<%si'%length 00824 buff.write(struct.pack(pattern, *_v10.mask)) 00825 _v14 = _v10.image 00826 _v15 = _v14.header 00827 buff.write(_struct_I.pack(_v15.seq)) 00828 _v16 = _v15.stamp 00829 _x = _v16 00830 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00831 _x = _v15.frame_id 00832 length = len(_x) 00833 buff.write(struct.pack('<I%ss'%length, length, _x)) 00834 _x = _v14 00835 buff.write(_struct_2I.pack(_x.height, _x.width)) 00836 _x = _v14.encoding 00837 length = len(_x) 00838 buff.write(struct.pack('<I%ss'%length, length, _x)) 00839 _x = _v14 00840 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 00841 _x = _v14.data 00842 length = len(_x) 00843 # - if encoded as a list instead, serialize as bytes instead of string 00844 if type(_x) in [list, tuple]: 00845 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00846 else: 00847 buff.write(struct.pack('<I%ss'%length, length, _x)) 00848 _v17 = _v10.disparity_image 00849 _v18 = _v17.header 00850 buff.write(_struct_I.pack(_v18.seq)) 00851 _v19 = _v18.stamp 00852 _x = _v19 00853 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00854 _x = _v18.frame_id 00855 length = len(_x) 00856 buff.write(struct.pack('<I%ss'%length, length, _x)) 00857 _x = _v17 00858 buff.write(_struct_2I.pack(_x.height, _x.width)) 00859 _x = _v17.encoding 00860 length = len(_x) 00861 buff.write(struct.pack('<I%ss'%length, length, _x)) 00862 _x = _v17 00863 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 00864 _x = _v17.data 00865 length = len(_x) 00866 # - if encoded as a list instead, serialize as bytes instead of string 00867 if type(_x) in [list, tuple]: 00868 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00869 else: 00870 buff.write(struct.pack('<I%ss'%length, length, _x)) 00871 _v20 = _v10.cam_info 00872 _v21 = _v20.header 00873 buff.write(_struct_I.pack(_v21.seq)) 00874 _v22 = _v21.stamp 00875 _x = _v22 00876 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00877 _x = _v21.frame_id 00878 length = len(_x) 00879 buff.write(struct.pack('<I%ss'%length, length, _x)) 00880 _x = _v20 00881 buff.write(_struct_2I.pack(_x.height, _x.width)) 00882 _x = _v20.distortion_model 00883 length = len(_x) 00884 buff.write(struct.pack('<I%ss'%length, length, _x)) 00885 length = len(_v20.D) 00886 buff.write(_struct_I.pack(length)) 00887 pattern = '<%sd'%length 00888 buff.write(struct.pack(pattern, *_v20.D)) 00889 buff.write(_struct_9d.pack(*_v20.K)) 00890 buff.write(_struct_9d.pack(*_v20.R)) 00891 buff.write(_struct_12d.pack(*_v20.P)) 00892 _x = _v20 00893 buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y)) 00894 _v23 = _v20.roi 00895 _x = _v23 00896 buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify)) 00897 _v24 = _v10.roi_box_pose 00898 _v25 = _v24.header 00899 buff.write(_struct_I.pack(_v25.seq)) 00900 _v26 = _v25.stamp 00901 _x = _v26 00902 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00903 _x = _v25.frame_id 00904 length = len(_x) 00905 buff.write(struct.pack('<I%ss'%length, length, _x)) 00906 _v27 = _v24.pose 00907 _v28 = _v27.position 00908 _x = _v28 00909 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00910 _v29 = _v27.orientation 00911 _x = _v29 00912 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00913 _v30 = _v10.roi_box_dims 00914 _x = _v30 00915 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00916 _x = val1.collision_name 00917 length = len(_x) 00918 buff.write(struct.pack('<I%ss'%length, length, _x)) 00919 _x = self 00920 buff.write(_struct_if3I.pack(_x.action_goal.goal.goal, _x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 00921 _x = self.action_result.header.frame_id 00922 length = len(_x) 00923 buff.write(struct.pack('<I%ss'%length, length, _x)) 00924 _x = self 00925 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 00926 _x = self.action_result.status.goal_id.id 00927 length = len(_x) 00928 buff.write(struct.pack('<I%ss'%length, length, _x)) 00929 buff.write(_struct_B.pack(self.action_result.status.status)) 00930 _x = self.action_result.status.text 00931 length = len(_x) 00932 buff.write(struct.pack('<I%ss'%length, length, _x)) 00933 _x = self 00934 buff.write(_struct_i3I.pack(_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 00935 _x = self.action_feedback.header.frame_id 00936 length = len(_x) 00937 buff.write(struct.pack('<I%ss'%length, length, _x)) 00938 _x = self 00939 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 00940 _x = self.action_feedback.status.goal_id.id 00941 length = len(_x) 00942 buff.write(struct.pack('<I%ss'%length, length, _x)) 00943 buff.write(_struct_B.pack(self.action_feedback.status.status)) 00944 _x = self.action_feedback.status.text 00945 length = len(_x) 00946 buff.write(struct.pack('<I%ss'%length, length, _x)) 00947 except struct.error as se: self._check_types(se) 00948 except TypeError as te: self._check_types(te) 00949 00950 def deserialize(self, str): 00951 """ 00952 unpack serialized message in str into this message instance 00953 @param str: byte array of serialized message 00954 @type str: str 00955 """ 00956 try: 00957 if self.action_goal is None: 00958 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal() 00959 if self.action_result is None: 00960 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult() 00961 if self.action_feedback is None: 00962 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback() 00963 end = 0 00964 _x = self 00965 start = end 00966 end += 12 00967 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00968 start = end 00969 end += 4 00970 (length,) = _struct_I.unpack(str[start:end]) 00971 start = end 00972 end += length 00973 self.action_goal.header.frame_id = str[start:end] 00974 _x = self 00975 start = end 00976 end += 8 00977 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00978 start = end 00979 end += 4 00980 (length,) = _struct_I.unpack(str[start:end]) 00981 start = end 00982 end += length 00983 self.action_goal.goal_id.id = str[start:end] 00984 _x = self 00985 start = end 00986 end += 12 00987 (_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00988 start = end 00989 end += 4 00990 (length,) = _struct_I.unpack(str[start:end]) 00991 start = end 00992 end += length 00993 self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end] 00994 start = end 00995 end += 4 00996 (length,) = _struct_I.unpack(str[start:end]) 00997 self.action_goal.goal.grasp.pre_grasp_posture.name = [] 00998 for i in range(0, length): 00999 start = end 01000 end += 4 01001 (length,) = _struct_I.unpack(str[start:end]) 01002 start = end 01003 end += length 01004 val1 = str[start:end] 01005 self.action_goal.goal.grasp.pre_grasp_posture.name.append(val1) 01006 start = end 01007 end += 4 01008 (length,) = _struct_I.unpack(str[start:end]) 01009 pattern = '<%sd'%length 01010 start = end 01011 end += struct.calcsize(pattern) 01012 self.action_goal.goal.grasp.pre_grasp_posture.position = struct.unpack(pattern, str[start:end]) 01013 start = end 01014 end += 4 01015 (length,) = _struct_I.unpack(str[start:end]) 01016 pattern = '<%sd'%length 01017 start = end 01018 end += struct.calcsize(pattern) 01019 self.action_goal.goal.grasp.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end]) 01020 start = end 01021 end += 4 01022 (length,) = _struct_I.unpack(str[start:end]) 01023 pattern = '<%sd'%length 01024 start = end 01025 end += struct.calcsize(pattern) 01026 self.action_goal.goal.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end]) 01027 _x = self 01028 start = end 01029 end += 12 01030 (_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01031 start = end 01032 end += 4 01033 (length,) = _struct_I.unpack(str[start:end]) 01034 start = end 01035 end += length 01036 self.action_goal.goal.grasp.grasp_posture.header.frame_id = str[start:end] 01037 start = end 01038 end += 4 01039 (length,) = _struct_I.unpack(str[start:end]) 01040 self.action_goal.goal.grasp.grasp_posture.name = [] 01041 for i in range(0, length): 01042 start = end 01043 end += 4 01044 (length,) = _struct_I.unpack(str[start:end]) 01045 start = end 01046 end += length 01047 val1 = str[start:end] 01048 self.action_goal.goal.grasp.grasp_posture.name.append(val1) 01049 start = end 01050 end += 4 01051 (length,) = _struct_I.unpack(str[start:end]) 01052 pattern = '<%sd'%length 01053 start = end 01054 end += struct.calcsize(pattern) 01055 self.action_goal.goal.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end]) 01056 start = end 01057 end += 4 01058 (length,) = _struct_I.unpack(str[start:end]) 01059 pattern = '<%sd'%length 01060 start = end 01061 end += struct.calcsize(pattern) 01062 self.action_goal.goal.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end]) 01063 start = end 01064 end += 4 01065 (length,) = _struct_I.unpack(str[start:end]) 01066 pattern = '<%sd'%length 01067 start = end 01068 end += struct.calcsize(pattern) 01069 self.action_goal.goal.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end]) 01070 _x = self 01071 start = end 01072 end += 73 01073 (_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.grasp.desired_approach_distance, _x.action_goal.goal.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end]) 01074 self.action_goal.goal.grasp.cluster_rep = bool(self.action_goal.goal.grasp.cluster_rep) 01075 start = end 01076 end += 4 01077 (length,) = _struct_I.unpack(str[start:end]) 01078 self.action_goal.goal.grasp.moved_obstacles = [] 01079 for i in range(0, length): 01080 val1 = object_manipulation_msgs.msg.GraspableObject() 01081 start = end 01082 end += 4 01083 (length,) = _struct_I.unpack(str[start:end]) 01084 start = end 01085 end += length 01086 val1.reference_frame_id = str[start:end] 01087 start = end 01088 end += 4 01089 (length,) = _struct_I.unpack(str[start:end]) 01090 val1.potential_models = [] 01091 for i in range(0, length): 01092 val2 = household_objects_database_msgs.msg.DatabaseModelPose() 01093 start = end 01094 end += 4 01095 (val2.model_id,) = _struct_i.unpack(str[start:end]) 01096 _v31 = val2.pose 01097 _v32 = _v31.header 01098 start = end 01099 end += 4 01100 (_v32.seq,) = _struct_I.unpack(str[start:end]) 01101 _v33 = _v32.stamp 01102 _x = _v33 01103 start = end 01104 end += 8 01105 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01106 start = end 01107 end += 4 01108 (length,) = _struct_I.unpack(str[start:end]) 01109 start = end 01110 end += length 01111 _v32.frame_id = str[start:end] 01112 _v34 = _v31.pose 01113 _v35 = _v34.position 01114 _x = _v35 01115 start = end 01116 end += 24 01117 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01118 _v36 = _v34.orientation 01119 _x = _v36 01120 start = end 01121 end += 32 01122 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01123 start = end 01124 end += 4 01125 (val2.confidence,) = _struct_f.unpack(str[start:end]) 01126 start = end 01127 end += 4 01128 (length,) = _struct_I.unpack(str[start:end]) 01129 start = end 01130 end += length 01131 val2.detector_name = str[start:end] 01132 val1.potential_models.append(val2) 01133 _v37 = val1.cluster 01134 _v38 = _v37.header 01135 start = end 01136 end += 4 01137 (_v38.seq,) = _struct_I.unpack(str[start:end]) 01138 _v39 = _v38.stamp 01139 _x = _v39 01140 start = end 01141 end += 8 01142 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01143 start = end 01144 end += 4 01145 (length,) = _struct_I.unpack(str[start:end]) 01146 start = end 01147 end += length 01148 _v38.frame_id = str[start:end] 01149 start = end 01150 end += 4 01151 (length,) = _struct_I.unpack(str[start:end]) 01152 _v37.points = [] 01153 for i in range(0, length): 01154 val3 = geometry_msgs.msg.Point32() 01155 _x = val3 01156 start = end 01157 end += 12 01158 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01159 _v37.points.append(val3) 01160 start = end 01161 end += 4 01162 (length,) = _struct_I.unpack(str[start:end]) 01163 _v37.channels = [] 01164 for i in range(0, length): 01165 val3 = sensor_msgs.msg.ChannelFloat32() 01166 start = end 01167 end += 4 01168 (length,) = _struct_I.unpack(str[start:end]) 01169 start = end 01170 end += length 01171 val3.name = str[start:end] 01172 start = end 01173 end += 4 01174 (length,) = _struct_I.unpack(str[start:end]) 01175 pattern = '<%sf'%length 01176 start = end 01177 end += struct.calcsize(pattern) 01178 val3.values = struct.unpack(pattern, str[start:end]) 01179 _v37.channels.append(val3) 01180 _v40 = val1.region 01181 _v41 = _v40.cloud 01182 _v42 = _v41.header 01183 start = end 01184 end += 4 01185 (_v42.seq,) = _struct_I.unpack(str[start:end]) 01186 _v43 = _v42.stamp 01187 _x = _v43 01188 start = end 01189 end += 8 01190 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01191 start = end 01192 end += 4 01193 (length,) = _struct_I.unpack(str[start:end]) 01194 start = end 01195 end += length 01196 _v42.frame_id = str[start:end] 01197 _x = _v41 01198 start = end 01199 end += 8 01200 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01201 start = end 01202 end += 4 01203 (length,) = _struct_I.unpack(str[start:end]) 01204 _v41.fields = [] 01205 for i in range(0, length): 01206 val4 = sensor_msgs.msg.PointField() 01207 start = end 01208 end += 4 01209 (length,) = _struct_I.unpack(str[start:end]) 01210 start = end 01211 end += length 01212 val4.name = str[start:end] 01213 _x = val4 01214 start = end 01215 end += 9 01216 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 01217 _v41.fields.append(val4) 01218 _x = _v41 01219 start = end 01220 end += 9 01221 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end]) 01222 _v41.is_bigendian = bool(_v41.is_bigendian) 01223 start = end 01224 end += 4 01225 (length,) = _struct_I.unpack(str[start:end]) 01226 start = end 01227 end += length 01228 _v41.data = str[start:end] 01229 start = end 01230 end += 1 01231 (_v41.is_dense,) = _struct_B.unpack(str[start:end]) 01232 _v41.is_dense = bool(_v41.is_dense) 01233 start = end 01234 end += 4 01235 (length,) = _struct_I.unpack(str[start:end]) 01236 pattern = '<%si'%length 01237 start = end 01238 end += struct.calcsize(pattern) 01239 _v40.mask = struct.unpack(pattern, str[start:end]) 01240 _v44 = _v40.image 01241 _v45 = _v44.header 01242 start = end 01243 end += 4 01244 (_v45.seq,) = _struct_I.unpack(str[start:end]) 01245 _v46 = _v45.stamp 01246 _x = _v46 01247 start = end 01248 end += 8 01249 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01250 start = end 01251 end += 4 01252 (length,) = _struct_I.unpack(str[start:end]) 01253 start = end 01254 end += length 01255 _v45.frame_id = str[start:end] 01256 _x = _v44 01257 start = end 01258 end += 8 01259 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01260 start = end 01261 end += 4 01262 (length,) = _struct_I.unpack(str[start:end]) 01263 start = end 01264 end += length 01265 _v44.encoding = str[start:end] 01266 _x = _v44 01267 start = end 01268 end += 5 01269 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 01270 start = end 01271 end += 4 01272 (length,) = _struct_I.unpack(str[start:end]) 01273 start = end 01274 end += length 01275 _v44.data = str[start:end] 01276 _v47 = _v40.disparity_image 01277 _v48 = _v47.header 01278 start = end 01279 end += 4 01280 (_v48.seq,) = _struct_I.unpack(str[start:end]) 01281 _v49 = _v48.stamp 01282 _x = _v49 01283 start = end 01284 end += 8 01285 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01286 start = end 01287 end += 4 01288 (length,) = _struct_I.unpack(str[start:end]) 01289 start = end 01290 end += length 01291 _v48.frame_id = str[start:end] 01292 _x = _v47 01293 start = end 01294 end += 8 01295 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01296 start = end 01297 end += 4 01298 (length,) = _struct_I.unpack(str[start:end]) 01299 start = end 01300 end += length 01301 _v47.encoding = str[start:end] 01302 _x = _v47 01303 start = end 01304 end += 5 01305 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 01306 start = end 01307 end += 4 01308 (length,) = _struct_I.unpack(str[start:end]) 01309 start = end 01310 end += length 01311 _v47.data = str[start:end] 01312 _v50 = _v40.cam_info 01313 _v51 = _v50.header 01314 start = end 01315 end += 4 01316 (_v51.seq,) = _struct_I.unpack(str[start:end]) 01317 _v52 = _v51.stamp 01318 _x = _v52 01319 start = end 01320 end += 8 01321 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01322 start = end 01323 end += 4 01324 (length,) = _struct_I.unpack(str[start:end]) 01325 start = end 01326 end += length 01327 _v51.frame_id = str[start:end] 01328 _x = _v50 01329 start = end 01330 end += 8 01331 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01332 start = end 01333 end += 4 01334 (length,) = _struct_I.unpack(str[start:end]) 01335 start = end 01336 end += length 01337 _v50.distortion_model = str[start:end] 01338 start = end 01339 end += 4 01340 (length,) = _struct_I.unpack(str[start:end]) 01341 pattern = '<%sd'%length 01342 start = end 01343 end += struct.calcsize(pattern) 01344 _v50.D = struct.unpack(pattern, str[start:end]) 01345 start = end 01346 end += 72 01347 _v50.K = _struct_9d.unpack(str[start:end]) 01348 start = end 01349 end += 72 01350 _v50.R = _struct_9d.unpack(str[start:end]) 01351 start = end 01352 end += 96 01353 _v50.P = _struct_12d.unpack(str[start:end]) 01354 _x = _v50 01355 start = end 01356 end += 8 01357 (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end]) 01358 _v53 = _v50.roi 01359 _x = _v53 01360 start = end 01361 end += 17 01362 (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end]) 01363 _v53.do_rectify = bool(_v53.do_rectify) 01364 _v54 = _v40.roi_box_pose 01365 _v55 = _v54.header 01366 start = end 01367 end += 4 01368 (_v55.seq,) = _struct_I.unpack(str[start:end]) 01369 _v56 = _v55.stamp 01370 _x = _v56 01371 start = end 01372 end += 8 01373 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01374 start = end 01375 end += 4 01376 (length,) = _struct_I.unpack(str[start:end]) 01377 start = end 01378 end += length 01379 _v55.frame_id = str[start:end] 01380 _v57 = _v54.pose 01381 _v58 = _v57.position 01382 _x = _v58 01383 start = end 01384 end += 24 01385 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01386 _v59 = _v57.orientation 01387 _x = _v59 01388 start = end 01389 end += 32 01390 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01391 _v60 = _v40.roi_box_dims 01392 _x = _v60 01393 start = end 01394 end += 24 01395 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01396 start = end 01397 end += 4 01398 (length,) = _struct_I.unpack(str[start:end]) 01399 start = end 01400 end += length 01401 val1.collision_name = str[start:end] 01402 self.action_goal.goal.grasp.moved_obstacles.append(val1) 01403 _x = self 01404 start = end 01405 end += 20 01406 (_x.action_goal.goal.goal, _x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_if3I.unpack(str[start:end]) 01407 start = end 01408 end += 4 01409 (length,) = _struct_I.unpack(str[start:end]) 01410 start = end 01411 end += length 01412 self.action_result.header.frame_id = str[start:end] 01413 _x = self 01414 start = end 01415 end += 8 01416 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 01417 start = end 01418 end += 4 01419 (length,) = _struct_I.unpack(str[start:end]) 01420 start = end 01421 end += length 01422 self.action_result.status.goal_id.id = str[start:end] 01423 start = end 01424 end += 1 01425 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 01426 start = end 01427 end += 4 01428 (length,) = _struct_I.unpack(str[start:end]) 01429 start = end 01430 end += length 01431 self.action_result.status.text = str[start:end] 01432 _x = self 01433 start = end 01434 end += 16 01435 (_x.action_result.result.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]) 01436 start = end 01437 end += 4 01438 (length,) = _struct_I.unpack(str[start:end]) 01439 start = end 01440 end += length 01441 self.action_feedback.header.frame_id = str[start:end] 01442 _x = self 01443 start = end 01444 end += 8 01445 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 01446 start = end 01447 end += 4 01448 (length,) = _struct_I.unpack(str[start:end]) 01449 start = end 01450 end += length 01451 self.action_feedback.status.goal_id.id = str[start:end] 01452 start = end 01453 end += 1 01454 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 01455 start = end 01456 end += 4 01457 (length,) = _struct_I.unpack(str[start:end]) 01458 start = end 01459 end += length 01460 self.action_feedback.status.text = str[start:end] 01461 return self 01462 except struct.error as e: 01463 raise roslib.message.DeserializationError(e) #most likely buffer underfill 01464 01465 01466 def serialize_numpy(self, buff, numpy): 01467 """ 01468 serialize message with numpy array types into buffer 01469 @param buff: buffer 01470 @type buff: StringIO 01471 @param numpy: numpy python module 01472 @type numpy module 01473 """ 01474 try: 01475 _x = self 01476 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs)) 01477 _x = self.action_goal.header.frame_id 01478 length = len(_x) 01479 buff.write(struct.pack('<I%ss'%length, length, _x)) 01480 _x = self 01481 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs)) 01482 _x = self.action_goal.goal_id.id 01483 length = len(_x) 01484 buff.write(struct.pack('<I%ss'%length, length, _x)) 01485 _x = self 01486 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs)) 01487 _x = self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id 01488 length = len(_x) 01489 buff.write(struct.pack('<I%ss'%length, length, _x)) 01490 length = len(self.action_goal.goal.grasp.pre_grasp_posture.name) 01491 buff.write(_struct_I.pack(length)) 01492 for val1 in self.action_goal.goal.grasp.pre_grasp_posture.name: 01493 length = len(val1) 01494 buff.write(struct.pack('<I%ss'%length, length, val1)) 01495 length = len(self.action_goal.goal.grasp.pre_grasp_posture.position) 01496 buff.write(_struct_I.pack(length)) 01497 pattern = '<%sd'%length 01498 buff.write(self.action_goal.goal.grasp.pre_grasp_posture.position.tostring()) 01499 length = len(self.action_goal.goal.grasp.pre_grasp_posture.velocity) 01500 buff.write(_struct_I.pack(length)) 01501 pattern = '<%sd'%length 01502 buff.write(self.action_goal.goal.grasp.pre_grasp_posture.velocity.tostring()) 01503 length = len(self.action_goal.goal.grasp.pre_grasp_posture.effort) 01504 buff.write(_struct_I.pack(length)) 01505 pattern = '<%sd'%length 01506 buff.write(self.action_goal.goal.grasp.pre_grasp_posture.effort.tostring()) 01507 _x = self 01508 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs)) 01509 _x = self.action_goal.goal.grasp.grasp_posture.header.frame_id 01510 length = len(_x) 01511 buff.write(struct.pack('<I%ss'%length, length, _x)) 01512 length = len(self.action_goal.goal.grasp.grasp_posture.name) 01513 buff.write(_struct_I.pack(length)) 01514 for val1 in self.action_goal.goal.grasp.grasp_posture.name: 01515 length = len(val1) 01516 buff.write(struct.pack('<I%ss'%length, length, val1)) 01517 length = len(self.action_goal.goal.grasp.grasp_posture.position) 01518 buff.write(_struct_I.pack(length)) 01519 pattern = '<%sd'%length 01520 buff.write(self.action_goal.goal.grasp.grasp_posture.position.tostring()) 01521 length = len(self.action_goal.goal.grasp.grasp_posture.velocity) 01522 buff.write(_struct_I.pack(length)) 01523 pattern = '<%sd'%length 01524 buff.write(self.action_goal.goal.grasp.grasp_posture.velocity.tostring()) 01525 length = len(self.action_goal.goal.grasp.grasp_posture.effort) 01526 buff.write(_struct_I.pack(length)) 01527 pattern = '<%sd'%length 01528 buff.write(self.action_goal.goal.grasp.grasp_posture.effort.tostring()) 01529 _x = self 01530 buff.write(_struct_8dB2f.pack(_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.grasp.desired_approach_distance, _x.action_goal.goal.grasp.min_approach_distance)) 01531 length = len(self.action_goal.goal.grasp.moved_obstacles) 01532 buff.write(_struct_I.pack(length)) 01533 for val1 in self.action_goal.goal.grasp.moved_obstacles: 01534 _x = val1.reference_frame_id 01535 length = len(_x) 01536 buff.write(struct.pack('<I%ss'%length, length, _x)) 01537 length = len(val1.potential_models) 01538 buff.write(_struct_I.pack(length)) 01539 for val2 in val1.potential_models: 01540 buff.write(_struct_i.pack(val2.model_id)) 01541 _v61 = val2.pose 01542 _v62 = _v61.header 01543 buff.write(_struct_I.pack(_v62.seq)) 01544 _v63 = _v62.stamp 01545 _x = _v63 01546 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01547 _x = _v62.frame_id 01548 length = len(_x) 01549 buff.write(struct.pack('<I%ss'%length, length, _x)) 01550 _v64 = _v61.pose 01551 _v65 = _v64.position 01552 _x = _v65 01553 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01554 _v66 = _v64.orientation 01555 _x = _v66 01556 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01557 buff.write(_struct_f.pack(val2.confidence)) 01558 _x = val2.detector_name 01559 length = len(_x) 01560 buff.write(struct.pack('<I%ss'%length, length, _x)) 01561 _v67 = val1.cluster 01562 _v68 = _v67.header 01563 buff.write(_struct_I.pack(_v68.seq)) 01564 _v69 = _v68.stamp 01565 _x = _v69 01566 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01567 _x = _v68.frame_id 01568 length = len(_x) 01569 buff.write(struct.pack('<I%ss'%length, length, _x)) 01570 length = len(_v67.points) 01571 buff.write(_struct_I.pack(length)) 01572 for val3 in _v67.points: 01573 _x = val3 01574 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 01575 length = len(_v67.channels) 01576 buff.write(_struct_I.pack(length)) 01577 for val3 in _v67.channels: 01578 _x = val3.name 01579 length = len(_x) 01580 buff.write(struct.pack('<I%ss'%length, length, _x)) 01581 length = len(val3.values) 01582 buff.write(_struct_I.pack(length)) 01583 pattern = '<%sf'%length 01584 buff.write(val3.values.tostring()) 01585 _v70 = val1.region 01586 _v71 = _v70.cloud 01587 _v72 = _v71.header 01588 buff.write(_struct_I.pack(_v72.seq)) 01589 _v73 = _v72.stamp 01590 _x = _v73 01591 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01592 _x = _v72.frame_id 01593 length = len(_x) 01594 buff.write(struct.pack('<I%ss'%length, length, _x)) 01595 _x = _v71 01596 buff.write(_struct_2I.pack(_x.height, _x.width)) 01597 length = len(_v71.fields) 01598 buff.write(_struct_I.pack(length)) 01599 for val4 in _v71.fields: 01600 _x = val4.name 01601 length = len(_x) 01602 buff.write(struct.pack('<I%ss'%length, length, _x)) 01603 _x = val4 01604 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count)) 01605 _x = _v71 01606 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step)) 01607 _x = _v71.data 01608 length = len(_x) 01609 # - if encoded as a list instead, serialize as bytes instead of string 01610 if type(_x) in [list, tuple]: 01611 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01612 else: 01613 buff.write(struct.pack('<I%ss'%length, length, _x)) 01614 buff.write(_struct_B.pack(_v71.is_dense)) 01615 length = len(_v70.mask) 01616 buff.write(_struct_I.pack(length)) 01617 pattern = '<%si'%length 01618 buff.write(_v70.mask.tostring()) 01619 _v74 = _v70.image 01620 _v75 = _v74.header 01621 buff.write(_struct_I.pack(_v75.seq)) 01622 _v76 = _v75.stamp 01623 _x = _v76 01624 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01625 _x = _v75.frame_id 01626 length = len(_x) 01627 buff.write(struct.pack('<I%ss'%length, length, _x)) 01628 _x = _v74 01629 buff.write(_struct_2I.pack(_x.height, _x.width)) 01630 _x = _v74.encoding 01631 length = len(_x) 01632 buff.write(struct.pack('<I%ss'%length, length, _x)) 01633 _x = _v74 01634 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 01635 _x = _v74.data 01636 length = len(_x) 01637 # - if encoded as a list instead, serialize as bytes instead of string 01638 if type(_x) in [list, tuple]: 01639 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01640 else: 01641 buff.write(struct.pack('<I%ss'%length, length, _x)) 01642 _v77 = _v70.disparity_image 01643 _v78 = _v77.header 01644 buff.write(_struct_I.pack(_v78.seq)) 01645 _v79 = _v78.stamp 01646 _x = _v79 01647 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01648 _x = _v78.frame_id 01649 length = len(_x) 01650 buff.write(struct.pack('<I%ss'%length, length, _x)) 01651 _x = _v77 01652 buff.write(_struct_2I.pack(_x.height, _x.width)) 01653 _x = _v77.encoding 01654 length = len(_x) 01655 buff.write(struct.pack('<I%ss'%length, length, _x)) 01656 _x = _v77 01657 buff.write(_struct_BI.pack(_x.is_bigendian, _x.step)) 01658 _x = _v77.data 01659 length = len(_x) 01660 # - if encoded as a list instead, serialize as bytes instead of string 01661 if type(_x) in [list, tuple]: 01662 buff.write(struct.pack('<I%sB'%length, length, *_x)) 01663 else: 01664 buff.write(struct.pack('<I%ss'%length, length, _x)) 01665 _v80 = _v70.cam_info 01666 _v81 = _v80.header 01667 buff.write(_struct_I.pack(_v81.seq)) 01668 _v82 = _v81.stamp 01669 _x = _v82 01670 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01671 _x = _v81.frame_id 01672 length = len(_x) 01673 buff.write(struct.pack('<I%ss'%length, length, _x)) 01674 _x = _v80 01675 buff.write(_struct_2I.pack(_x.height, _x.width)) 01676 _x = _v80.distortion_model 01677 length = len(_x) 01678 buff.write(struct.pack('<I%ss'%length, length, _x)) 01679 length = len(_v80.D) 01680 buff.write(_struct_I.pack(length)) 01681 pattern = '<%sd'%length 01682 buff.write(_v80.D.tostring()) 01683 buff.write(_v80.K.tostring()) 01684 buff.write(_v80.R.tostring()) 01685 buff.write(_v80.P.tostring()) 01686 _x = _v80 01687 buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y)) 01688 _v83 = _v80.roi 01689 _x = _v83 01690 buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify)) 01691 _v84 = _v70.roi_box_pose 01692 _v85 = _v84.header 01693 buff.write(_struct_I.pack(_v85.seq)) 01694 _v86 = _v85.stamp 01695 _x = _v86 01696 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01697 _x = _v85.frame_id 01698 length = len(_x) 01699 buff.write(struct.pack('<I%ss'%length, length, _x)) 01700 _v87 = _v84.pose 01701 _v88 = _v87.position 01702 _x = _v88 01703 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01704 _v89 = _v87.orientation 01705 _x = _v89 01706 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01707 _v90 = _v70.roi_box_dims 01708 _x = _v90 01709 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01710 _x = val1.collision_name 01711 length = len(_x) 01712 buff.write(struct.pack('<I%ss'%length, length, _x)) 01713 _x = self 01714 buff.write(_struct_if3I.pack(_x.action_goal.goal.goal, _x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs)) 01715 _x = self.action_result.header.frame_id 01716 length = len(_x) 01717 buff.write(struct.pack('<I%ss'%length, length, _x)) 01718 _x = self 01719 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs)) 01720 _x = self.action_result.status.goal_id.id 01721 length = len(_x) 01722 buff.write(struct.pack('<I%ss'%length, length, _x)) 01723 buff.write(_struct_B.pack(self.action_result.status.status)) 01724 _x = self.action_result.status.text 01725 length = len(_x) 01726 buff.write(struct.pack('<I%ss'%length, length, _x)) 01727 _x = self 01728 buff.write(_struct_i3I.pack(_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs)) 01729 _x = self.action_feedback.header.frame_id 01730 length = len(_x) 01731 buff.write(struct.pack('<I%ss'%length, length, _x)) 01732 _x = self 01733 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs)) 01734 _x = self.action_feedback.status.goal_id.id 01735 length = len(_x) 01736 buff.write(struct.pack('<I%ss'%length, length, _x)) 01737 buff.write(_struct_B.pack(self.action_feedback.status.status)) 01738 _x = self.action_feedback.status.text 01739 length = len(_x) 01740 buff.write(struct.pack('<I%ss'%length, length, _x)) 01741 except struct.error as se: self._check_types(se) 01742 except TypeError as te: self._check_types(te) 01743 01744 def deserialize_numpy(self, str, numpy): 01745 """ 01746 unpack serialized message in str into this message instance using numpy for array types 01747 @param str: byte array of serialized message 01748 @type str: str 01749 @param numpy: numpy python module 01750 @type numpy: module 01751 """ 01752 try: 01753 if self.action_goal is None: 01754 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal() 01755 if self.action_result is None: 01756 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult() 01757 if self.action_feedback is None: 01758 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback() 01759 end = 0 01760 _x = self 01761 start = end 01762 end += 12 01763 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01764 start = end 01765 end += 4 01766 (length,) = _struct_I.unpack(str[start:end]) 01767 start = end 01768 end += length 01769 self.action_goal.header.frame_id = str[start:end] 01770 _x = self 01771 start = end 01772 end += 8 01773 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 01774 start = end 01775 end += 4 01776 (length,) = _struct_I.unpack(str[start:end]) 01777 start = end 01778 end += length 01779 self.action_goal.goal_id.id = str[start:end] 01780 _x = self 01781 start = end 01782 end += 12 01783 (_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01784 start = end 01785 end += 4 01786 (length,) = _struct_I.unpack(str[start:end]) 01787 start = end 01788 end += length 01789 self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end] 01790 start = end 01791 end += 4 01792 (length,) = _struct_I.unpack(str[start:end]) 01793 self.action_goal.goal.grasp.pre_grasp_posture.name = [] 01794 for i in range(0, length): 01795 start = end 01796 end += 4 01797 (length,) = _struct_I.unpack(str[start:end]) 01798 start = end 01799 end += length 01800 val1 = str[start:end] 01801 self.action_goal.goal.grasp.pre_grasp_posture.name.append(val1) 01802 start = end 01803 end += 4 01804 (length,) = _struct_I.unpack(str[start:end]) 01805 pattern = '<%sd'%length 01806 start = end 01807 end += struct.calcsize(pattern) 01808 self.action_goal.goal.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01809 start = end 01810 end += 4 01811 (length,) = _struct_I.unpack(str[start:end]) 01812 pattern = '<%sd'%length 01813 start = end 01814 end += struct.calcsize(pattern) 01815 self.action_goal.goal.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01816 start = end 01817 end += 4 01818 (length,) = _struct_I.unpack(str[start:end]) 01819 pattern = '<%sd'%length 01820 start = end 01821 end += struct.calcsize(pattern) 01822 self.action_goal.goal.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01823 _x = self 01824 start = end 01825 end += 12 01826 (_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01827 start = end 01828 end += 4 01829 (length,) = _struct_I.unpack(str[start:end]) 01830 start = end 01831 end += length 01832 self.action_goal.goal.grasp.grasp_posture.header.frame_id = str[start:end] 01833 start = end 01834 end += 4 01835 (length,) = _struct_I.unpack(str[start:end]) 01836 self.action_goal.goal.grasp.grasp_posture.name = [] 01837 for i in range(0, length): 01838 start = end 01839 end += 4 01840 (length,) = _struct_I.unpack(str[start:end]) 01841 start = end 01842 end += length 01843 val1 = str[start:end] 01844 self.action_goal.goal.grasp.grasp_posture.name.append(val1) 01845 start = end 01846 end += 4 01847 (length,) = _struct_I.unpack(str[start:end]) 01848 pattern = '<%sd'%length 01849 start = end 01850 end += struct.calcsize(pattern) 01851 self.action_goal.goal.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01852 start = end 01853 end += 4 01854 (length,) = _struct_I.unpack(str[start:end]) 01855 pattern = '<%sd'%length 01856 start = end 01857 end += struct.calcsize(pattern) 01858 self.action_goal.goal.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01859 start = end 01860 end += 4 01861 (length,) = _struct_I.unpack(str[start:end]) 01862 pattern = '<%sd'%length 01863 start = end 01864 end += struct.calcsize(pattern) 01865 self.action_goal.goal.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01866 _x = self 01867 start = end 01868 end += 73 01869 (_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.grasp.desired_approach_distance, _x.action_goal.goal.grasp.min_approach_distance,) = _struct_8dB2f.unpack(str[start:end]) 01870 self.action_goal.goal.grasp.cluster_rep = bool(self.action_goal.goal.grasp.cluster_rep) 01871 start = end 01872 end += 4 01873 (length,) = _struct_I.unpack(str[start:end]) 01874 self.action_goal.goal.grasp.moved_obstacles = [] 01875 for i in range(0, length): 01876 val1 = object_manipulation_msgs.msg.GraspableObject() 01877 start = end 01878 end += 4 01879 (length,) = _struct_I.unpack(str[start:end]) 01880 start = end 01881 end += length 01882 val1.reference_frame_id = str[start:end] 01883 start = end 01884 end += 4 01885 (length,) = _struct_I.unpack(str[start:end]) 01886 val1.potential_models = [] 01887 for i in range(0, length): 01888 val2 = household_objects_database_msgs.msg.DatabaseModelPose() 01889 start = end 01890 end += 4 01891 (val2.model_id,) = _struct_i.unpack(str[start:end]) 01892 _v91 = val2.pose 01893 _v92 = _v91.header 01894 start = end 01895 end += 4 01896 (_v92.seq,) = _struct_I.unpack(str[start:end]) 01897 _v93 = _v92.stamp 01898 _x = _v93 01899 start = end 01900 end += 8 01901 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01902 start = end 01903 end += 4 01904 (length,) = _struct_I.unpack(str[start:end]) 01905 start = end 01906 end += length 01907 _v92.frame_id = str[start:end] 01908 _v94 = _v91.pose 01909 _v95 = _v94.position 01910 _x = _v95 01911 start = end 01912 end += 24 01913 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01914 _v96 = _v94.orientation 01915 _x = _v96 01916 start = end 01917 end += 32 01918 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01919 start = end 01920 end += 4 01921 (val2.confidence,) = _struct_f.unpack(str[start:end]) 01922 start = end 01923 end += 4 01924 (length,) = _struct_I.unpack(str[start:end]) 01925 start = end 01926 end += length 01927 val2.detector_name = str[start:end] 01928 val1.potential_models.append(val2) 01929 _v97 = val1.cluster 01930 _v98 = _v97.header 01931 start = end 01932 end += 4 01933 (_v98.seq,) = _struct_I.unpack(str[start:end]) 01934 _v99 = _v98.stamp 01935 _x = _v99 01936 start = end 01937 end += 8 01938 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01939 start = end 01940 end += 4 01941 (length,) = _struct_I.unpack(str[start:end]) 01942 start = end 01943 end += length 01944 _v98.frame_id = str[start:end] 01945 start = end 01946 end += 4 01947 (length,) = _struct_I.unpack(str[start:end]) 01948 _v97.points = [] 01949 for i in range(0, length): 01950 val3 = geometry_msgs.msg.Point32() 01951 _x = val3 01952 start = end 01953 end += 12 01954 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01955 _v97.points.append(val3) 01956 start = end 01957 end += 4 01958 (length,) = _struct_I.unpack(str[start:end]) 01959 _v97.channels = [] 01960 for i in range(0, length): 01961 val3 = sensor_msgs.msg.ChannelFloat32() 01962 start = end 01963 end += 4 01964 (length,) = _struct_I.unpack(str[start:end]) 01965 start = end 01966 end += length 01967 val3.name = str[start:end] 01968 start = end 01969 end += 4 01970 (length,) = _struct_I.unpack(str[start:end]) 01971 pattern = '<%sf'%length 01972 start = end 01973 end += struct.calcsize(pattern) 01974 val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 01975 _v97.channels.append(val3) 01976 _v100 = val1.region 01977 _v101 = _v100.cloud 01978 _v102 = _v101.header 01979 start = end 01980 end += 4 01981 (_v102.seq,) = _struct_I.unpack(str[start:end]) 01982 _v103 = _v102.stamp 01983 _x = _v103 01984 start = end 01985 end += 8 01986 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01987 start = end 01988 end += 4 01989 (length,) = _struct_I.unpack(str[start:end]) 01990 start = end 01991 end += length 01992 _v102.frame_id = str[start:end] 01993 _x = _v101 01994 start = end 01995 end += 8 01996 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 01997 start = end 01998 end += 4 01999 (length,) = _struct_I.unpack(str[start:end]) 02000 _v101.fields = [] 02001 for i in range(0, length): 02002 val4 = sensor_msgs.msg.PointField() 02003 start = end 02004 end += 4 02005 (length,) = _struct_I.unpack(str[start:end]) 02006 start = end 02007 end += length 02008 val4.name = str[start:end] 02009 _x = val4 02010 start = end 02011 end += 9 02012 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end]) 02013 _v101.fields.append(val4) 02014 _x = _v101 02015 start = end 02016 end += 9 02017 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end]) 02018 _v101.is_bigendian = bool(_v101.is_bigendian) 02019 start = end 02020 end += 4 02021 (length,) = _struct_I.unpack(str[start:end]) 02022 start = end 02023 end += length 02024 _v101.data = str[start:end] 02025 start = end 02026 end += 1 02027 (_v101.is_dense,) = _struct_B.unpack(str[start:end]) 02028 _v101.is_dense = bool(_v101.is_dense) 02029 start = end 02030 end += 4 02031 (length,) = _struct_I.unpack(str[start:end]) 02032 pattern = '<%si'%length 02033 start = end 02034 end += struct.calcsize(pattern) 02035 _v100.mask = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 02036 _v104 = _v100.image 02037 _v105 = _v104.header 02038 start = end 02039 end += 4 02040 (_v105.seq,) = _struct_I.unpack(str[start:end]) 02041 _v106 = _v105.stamp 02042 _x = _v106 02043 start = end 02044 end += 8 02045 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02046 start = end 02047 end += 4 02048 (length,) = _struct_I.unpack(str[start:end]) 02049 start = end 02050 end += length 02051 _v105.frame_id = str[start:end] 02052 _x = _v104 02053 start = end 02054 end += 8 02055 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02056 start = end 02057 end += 4 02058 (length,) = _struct_I.unpack(str[start:end]) 02059 start = end 02060 end += length 02061 _v104.encoding = str[start:end] 02062 _x = _v104 02063 start = end 02064 end += 5 02065 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 02066 start = end 02067 end += 4 02068 (length,) = _struct_I.unpack(str[start:end]) 02069 start = end 02070 end += length 02071 _v104.data = str[start:end] 02072 _v107 = _v100.disparity_image 02073 _v108 = _v107.header 02074 start = end 02075 end += 4 02076 (_v108.seq,) = _struct_I.unpack(str[start:end]) 02077 _v109 = _v108.stamp 02078 _x = _v109 02079 start = end 02080 end += 8 02081 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02082 start = end 02083 end += 4 02084 (length,) = _struct_I.unpack(str[start:end]) 02085 start = end 02086 end += length 02087 _v108.frame_id = str[start:end] 02088 _x = _v107 02089 start = end 02090 end += 8 02091 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02092 start = end 02093 end += 4 02094 (length,) = _struct_I.unpack(str[start:end]) 02095 start = end 02096 end += length 02097 _v107.encoding = str[start:end] 02098 _x = _v107 02099 start = end 02100 end += 5 02101 (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end]) 02102 start = end 02103 end += 4 02104 (length,) = _struct_I.unpack(str[start:end]) 02105 start = end 02106 end += length 02107 _v107.data = str[start:end] 02108 _v110 = _v100.cam_info 02109 _v111 = _v110.header 02110 start = end 02111 end += 4 02112 (_v111.seq,) = _struct_I.unpack(str[start:end]) 02113 _v112 = _v111.stamp 02114 _x = _v112 02115 start = end 02116 end += 8 02117 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02118 start = end 02119 end += 4 02120 (length,) = _struct_I.unpack(str[start:end]) 02121 start = end 02122 end += length 02123 _v111.frame_id = str[start:end] 02124 _x = _v110 02125 start = end 02126 end += 8 02127 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end]) 02128 start = end 02129 end += 4 02130 (length,) = _struct_I.unpack(str[start:end]) 02131 start = end 02132 end += length 02133 _v110.distortion_model = str[start:end] 02134 start = end 02135 end += 4 02136 (length,) = _struct_I.unpack(str[start:end]) 02137 pattern = '<%sd'%length 02138 start = end 02139 end += struct.calcsize(pattern) 02140 _v110.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 02141 start = end 02142 end += 72 02143 _v110.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 02144 start = end 02145 end += 72 02146 _v110.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 02147 start = end 02148 end += 96 02149 _v110.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12) 02150 _x = _v110 02151 start = end 02152 end += 8 02153 (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end]) 02154 _v113 = _v110.roi 02155 _x = _v113 02156 start = end 02157 end += 17 02158 (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end]) 02159 _v113.do_rectify = bool(_v113.do_rectify) 02160 _v114 = _v100.roi_box_pose 02161 _v115 = _v114.header 02162 start = end 02163 end += 4 02164 (_v115.seq,) = _struct_I.unpack(str[start:end]) 02165 _v116 = _v115.stamp 02166 _x = _v116 02167 start = end 02168 end += 8 02169 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 02170 start = end 02171 end += 4 02172 (length,) = _struct_I.unpack(str[start:end]) 02173 start = end 02174 end += length 02175 _v115.frame_id = str[start:end] 02176 _v117 = _v114.pose 02177 _v118 = _v117.position 02178 _x = _v118 02179 start = end 02180 end += 24 02181 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 02182 _v119 = _v117.orientation 02183 _x = _v119 02184 start = end 02185 end += 32 02186 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 02187 _v120 = _v100.roi_box_dims 02188 _x = _v120 02189 start = end 02190 end += 24 02191 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 02192 start = end 02193 end += 4 02194 (length,) = _struct_I.unpack(str[start:end]) 02195 start = end 02196 end += length 02197 val1.collision_name = str[start:end] 02198 self.action_goal.goal.grasp.moved_obstacles.append(val1) 02199 _x = self 02200 start = end 02201 end += 20 02202 (_x.action_goal.goal.goal, _x.action_goal.goal.max_contact_force, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_if3I.unpack(str[start:end]) 02203 start = end 02204 end += 4 02205 (length,) = _struct_I.unpack(str[start:end]) 02206 start = end 02207 end += length 02208 self.action_result.header.frame_id = str[start:end] 02209 _x = self 02210 start = end 02211 end += 8 02212 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 02213 start = end 02214 end += 4 02215 (length,) = _struct_I.unpack(str[start:end]) 02216 start = end 02217 end += length 02218 self.action_result.status.goal_id.id = str[start:end] 02219 start = end 02220 end += 1 02221 (self.action_result.status.status,) = _struct_B.unpack(str[start:end]) 02222 start = end 02223 end += 4 02224 (length,) = _struct_I.unpack(str[start:end]) 02225 start = end 02226 end += length 02227 self.action_result.status.text = str[start:end] 02228 _x = self 02229 start = end 02230 end += 16 02231 (_x.action_result.result.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]) 02232 start = end 02233 end += 4 02234 (length,) = _struct_I.unpack(str[start:end]) 02235 start = end 02236 end += length 02237 self.action_feedback.header.frame_id = str[start:end] 02238 _x = self 02239 start = end 02240 end += 8 02241 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 02242 start = end 02243 end += 4 02244 (length,) = _struct_I.unpack(str[start:end]) 02245 start = end 02246 end += length 02247 self.action_feedback.status.goal_id.id = str[start:end] 02248 start = end 02249 end += 1 02250 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end]) 02251 start = end 02252 end += 4 02253 (length,) = _struct_I.unpack(str[start:end]) 02254 start = end 02255 end += length 02256 self.action_feedback.status.text = str[start:end] 02257 return self 02258 except struct.error as e: 02259 raise roslib.message.DeserializationError(e) #most likely buffer underfill 02260 02261 _struct_I = roslib.message.struct_I 02262 _struct_IBI = struct.Struct("<IBI") 02263 _struct_8dB2f = struct.Struct("<8dB2f") 02264 _struct_12d = struct.Struct("<12d") 02265 _struct_f = struct.Struct("<f") 02266 _struct_i = struct.Struct("<i") 02267 _struct_if3I = struct.Struct("<if3I") 02268 _struct_BI = struct.Struct("<BI") 02269 _struct_3f = struct.Struct("<3f") 02270 _struct_3I = struct.Struct("<3I") 02271 _struct_B = struct.Struct("<B") 02272 _struct_9d = struct.Struct("<9d") 02273 _struct_B2I = struct.Struct("<B2I") 02274 _struct_i3I = struct.Struct("<i3I") 02275 _struct_4d = struct.Struct("<4d") 02276 _struct_2I = struct.Struct("<2I") 02277 _struct_4IB = struct.Struct("<4IB") 02278 _struct_3d = struct.Struct("<3d")