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