_PickupActionResult.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/PickupActionResult.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 import object_manipulation_msgs.msg
00008 import actionlib_msgs.msg
00009 import manipulation_msgs.msg
00010 import geometry_msgs.msg
00011 import sensor_msgs.msg
00012 import genpy
00013 import std_msgs.msg
00014 
00015 class PickupActionResult(genpy.Message):
00016   _md5sum = "f8f466525b158e795c4b9c335cd7df4b"
00017   _type = "object_manipulation_msgs/PickupActionResult"
00018   _has_header = True #flag to mark the presence of a Header object
00019   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00020 
00021 Header header
00022 actionlib_msgs/GoalStatus status
00023 PickupResult result
00024 
00025 ================================================================================
00026 MSG: std_msgs/Header
00027 # Standard metadata for higher-level stamped data types.
00028 # This is generally used to communicate timestamped data 
00029 # in a particular coordinate frame.
00030 # 
00031 # sequence ID: consecutively increasing ID 
00032 uint32 seq
00033 #Two-integer timestamp that is expressed as:
00034 # * stamp.secs: seconds (stamp_secs) since epoch
00035 # * stamp.nsecs: nanoseconds since stamp_secs
00036 # time-handling sugar is provided by the client library
00037 time stamp
00038 #Frame this data is associated with
00039 # 0: no frame
00040 # 1: global frame
00041 string frame_id
00042 
00043 ================================================================================
00044 MSG: actionlib_msgs/GoalStatus
00045 GoalID goal_id
00046 uint8 status
00047 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00048 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00049 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00050                             #   and has since completed its execution (Terminal State)
00051 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00052 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00053                             #    to some failure (Terminal State)
00054 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00055                             #    because the goal was unattainable or invalid (Terminal State)
00056 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00057                             #    and has not yet completed execution
00058 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00059                             #    but the action server has not yet confirmed that the goal is canceled
00060 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00061                             #    and was successfully cancelled (Terminal State)
00062 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00063                             #    sent over the wire by an action server
00064 
00065 #Allow for the user to associate a string with GoalStatus for debugging
00066 string text
00067 
00068 
00069 ================================================================================
00070 MSG: actionlib_msgs/GoalID
00071 # The stamp should store the time at which this goal was requested.
00072 # It is used by an action server when it tries to preempt all
00073 # goals that were requested before a certain time
00074 time stamp
00075 
00076 # The id provides a way to associate feedback and
00077 # result message with specific goal requests. The id
00078 # specified must be unique.
00079 string id
00080 
00081 
00082 ================================================================================
00083 MSG: object_manipulation_msgs/PickupResult
00084 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00085 
00086 # The overall result of the pickup attempt
00087 ManipulationResult manipulation_result
00088 
00089 # The performed grasp, if attempt was successful
00090 manipulation_msgs/Grasp grasp
00091 
00092 # the complete list of attempted grasp, in the order in which they have been attempted
00093 # the successful one should be the last one in this list
00094 manipulation_msgs/Grasp[] attempted_grasps
00095 
00096 # the outcomes of the attempted grasps, in the same order as attempted_grasps
00097 GraspResult[] attempted_grasp_results
00098 
00099 
00100 ================================================================================
00101 MSG: object_manipulation_msgs/ManipulationResult
00102 # Result codes for manipulation tasks
00103 
00104 # task completed as expected
00105 # generally means you can proceed as planned
00106 int32 SUCCESS = 1
00107 
00108 # task not possible (e.g. out of reach or obstacles in the way)
00109 # generally means that the world was not disturbed, so you can try another task
00110 int32 UNFEASIBLE = -1
00111 
00112 # task was thought possible, but failed due to unexpected events during execution
00113 # it is likely that the world was disturbed, so you are encouraged to refresh
00114 # your sensed world model before proceeding to another task
00115 int32 FAILED = -2
00116 
00117 # a lower level error prevented task completion (e.g. joint controller not responding)
00118 # generally requires human attention
00119 int32 ERROR = -3
00120 
00121 # means that at some point during execution we ended up in a state that the collision-aware
00122 # arm navigation module will not move out of. The world was likely not disturbed, but you 
00123 # probably need a new collision map to move the arm out of the stuck position
00124 int32 ARM_MOVEMENT_PREVENTED = -4
00125 
00126 # specific to grasp actions
00127 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00128 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00129 int32 LIFT_FAILED = -5
00130 
00131 # specific to place actions
00132 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00133 # it is likely that the collision environment will see collisions between the hand and the object
00134 int32 RETREAT_FAILED = -6
00135 
00136 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00137 int32 CANCELLED = -7
00138 
00139 # the actual value of this error code
00140 int32 value
00141 
00142 ================================================================================
00143 MSG: manipulation_msgs/Grasp
00144 # A name for this grasp
00145 string id
00146 
00147 # The internal posture of the hand for the pre-grasp
00148 # only positions are used
00149 sensor_msgs/JointState pre_grasp_posture
00150 
00151 # The internal posture of the hand for the grasp
00152 # positions and efforts are used
00153 sensor_msgs/JointState grasp_posture
00154 
00155 # The position of the end-effector for the grasp relative to a reference frame 
00156 # (that is always specified elsewhere, not in this message)
00157 geometry_msgs/PoseStamped grasp_pose
00158 
00159 # The estimated probability of success for this grasp, or some other
00160 # measure of how "good" it is.
00161 float64 grasp_quality
00162 
00163 # The approach motion
00164 GripperTranslation approach
00165 
00166 # The retreat motion
00167 GripperTranslation retreat
00168 
00169 # the maximum contact force to use while grasping (<=0 to disable)
00170 float32 max_contact_force
00171 
00172 # an optional list of obstacles that we have semantic information about
00173 # and that can be touched/pushed/moved in the course of grasping
00174 string[] allowed_touch_objects
00175 
00176 ================================================================================
00177 MSG: sensor_msgs/JointState
00178 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00179 #
00180 # The state of each joint (revolute or prismatic) is defined by:
00181 #  * the position of the joint (rad or m),
00182 #  * the velocity of the joint (rad/s or m/s) and 
00183 #  * the effort that is applied in the joint (Nm or N).
00184 #
00185 # Each joint is uniquely identified by its name
00186 # The header specifies the time at which the joint states were recorded. All the joint states
00187 # in one message have to be recorded at the same time.
00188 #
00189 # This message consists of a multiple arrays, one for each part of the joint state. 
00190 # The goal is to make each of the fields optional. When e.g. your joints have no
00191 # effort associated with them, you can leave the effort array empty. 
00192 #
00193 # All arrays in this message should have the same size, or be empty.
00194 # This is the only way to uniquely associate the joint name with the correct
00195 # states.
00196 
00197 
00198 Header header
00199 
00200 string[] name
00201 float64[] position
00202 float64[] velocity
00203 float64[] effort
00204 
00205 ================================================================================
00206 MSG: geometry_msgs/PoseStamped
00207 # A Pose with reference coordinate frame and timestamp
00208 Header header
00209 Pose pose
00210 
00211 ================================================================================
00212 MSG: geometry_msgs/Pose
00213 # A representation of pose in free space, composed of postion and orientation. 
00214 Point position
00215 Quaternion orientation
00216 
00217 ================================================================================
00218 MSG: geometry_msgs/Point
00219 # This contains the position of a point in free space
00220 float64 x
00221 float64 y
00222 float64 z
00223 
00224 ================================================================================
00225 MSG: geometry_msgs/Quaternion
00226 # This represents an orientation in free space in quaternion form.
00227 
00228 float64 x
00229 float64 y
00230 float64 z
00231 float64 w
00232 
00233 ================================================================================
00234 MSG: manipulation_msgs/GripperTranslation
00235 # defines a translation for the gripper, used in pickup or place tasks
00236 # for example for lifting an object off a table or approaching the table for placing
00237 
00238 # the direction of the translation
00239 geometry_msgs/Vector3Stamped direction
00240 
00241 # the desired translation distance
00242 float32 desired_distance
00243 
00244 # the min distance that must be considered feasible before the
00245 # grasp is even attempted
00246 float32 min_distance
00247 
00248 ================================================================================
00249 MSG: geometry_msgs/Vector3Stamped
00250 # This represents a Vector3 with reference coordinate frame and timestamp
00251 Header header
00252 Vector3 vector
00253 
00254 ================================================================================
00255 MSG: geometry_msgs/Vector3
00256 # This represents a vector in free space. 
00257 
00258 float64 x
00259 float64 y
00260 float64 z
00261 ================================================================================
00262 MSG: object_manipulation_msgs/GraspResult
00263 int32 SUCCESS = 1
00264 int32 GRASP_OUT_OF_REACH = 2
00265 int32 GRASP_IN_COLLISION = 3
00266 int32 GRASP_UNFEASIBLE = 4
00267 int32 PREGRASP_OUT_OF_REACH = 5
00268 int32 PREGRASP_IN_COLLISION = 6
00269 int32 PREGRASP_UNFEASIBLE = 7
00270 int32 LIFT_OUT_OF_REACH = 8
00271 int32 LIFT_IN_COLLISION = 9
00272 int32 LIFT_UNFEASIBLE = 10
00273 int32 MOVE_ARM_FAILED = 11
00274 int32 GRASP_FAILED = 12
00275 int32 LIFT_FAILED = 13
00276 int32 RETREAT_FAILED = 14
00277 int32 result_code
00278 
00279 # whether the state of the world was disturbed by this attempt. generally, this flag
00280 # shows if another task can be attempted, or a new sensed world model is recommeded
00281 # before proceeding
00282 bool continuation_possible
00283 
00284 """
00285   __slots__ = ['header','status','result']
00286   _slot_types = ['std_msgs/Header','actionlib_msgs/GoalStatus','object_manipulation_msgs/PickupResult']
00287 
00288   def __init__(self, *args, **kwds):
00289     """
00290     Constructor. Any message fields that are implicitly/explicitly
00291     set to None will be assigned a default value. The recommend
00292     use is keyword arguments as this is more robust to future message
00293     changes.  You cannot mix in-order arguments and keyword arguments.
00294 
00295     The available fields are:
00296        header,status,result
00297 
00298     :param args: complete set of field values, in .msg order
00299     :param kwds: use keyword arguments corresponding to message field names
00300     to set specific fields.
00301     """
00302     if args or kwds:
00303       super(PickupActionResult, self).__init__(*args, **kwds)
00304       #message fields cannot be None, assign default values for those that are
00305       if self.header is None:
00306         self.header = std_msgs.msg.Header()
00307       if self.status is None:
00308         self.status = actionlib_msgs.msg.GoalStatus()
00309       if self.result is None:
00310         self.result = object_manipulation_msgs.msg.PickupResult()
00311     else:
00312       self.header = std_msgs.msg.Header()
00313       self.status = actionlib_msgs.msg.GoalStatus()
00314       self.result = object_manipulation_msgs.msg.PickupResult()
00315 
00316   def _get_types(self):
00317     """
00318     internal API method
00319     """
00320     return self._slot_types
00321 
00322   def serialize(self, buff):
00323     """
00324     serialize message into buffer
00325     :param buff: buffer, ``StringIO``
00326     """
00327     try:
00328       _x = self
00329       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00330       _x = self.header.frame_id
00331       length = len(_x)
00332       if python3 or type(_x) == unicode:
00333         _x = _x.encode('utf-8')
00334         length = len(_x)
00335       buff.write(struct.pack('<I%ss'%length, length, _x))
00336       _x = self
00337       buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00338       _x = self.status.goal_id.id
00339       length = len(_x)
00340       if python3 or type(_x) == unicode:
00341         _x = _x.encode('utf-8')
00342         length = len(_x)
00343       buff.write(struct.pack('<I%ss'%length, length, _x))
00344       buff.write(_struct_B.pack(self.status.status))
00345       _x = self.status.text
00346       length = len(_x)
00347       if python3 or type(_x) == unicode:
00348         _x = _x.encode('utf-8')
00349         length = len(_x)
00350       buff.write(struct.pack('<I%ss'%length, length, _x))
00351       buff.write(_struct_i.pack(self.result.manipulation_result.value))
00352       _x = self.result.grasp.id
00353       length = len(_x)
00354       if python3 or type(_x) == unicode:
00355         _x = _x.encode('utf-8')
00356         length = len(_x)
00357       buff.write(struct.pack('<I%ss'%length, length, _x))
00358       _x = self
00359       buff.write(_struct_3I.pack(_x.result.grasp.pre_grasp_posture.header.seq, _x.result.grasp.pre_grasp_posture.header.stamp.secs, _x.result.grasp.pre_grasp_posture.header.stamp.nsecs))
00360       _x = self.result.grasp.pre_grasp_posture.header.frame_id
00361       length = len(_x)
00362       if python3 or type(_x) == unicode:
00363         _x = _x.encode('utf-8')
00364         length = len(_x)
00365       buff.write(struct.pack('<I%ss'%length, length, _x))
00366       length = len(self.result.grasp.pre_grasp_posture.name)
00367       buff.write(_struct_I.pack(length))
00368       for val1 in self.result.grasp.pre_grasp_posture.name:
00369         length = len(val1)
00370         if python3 or type(val1) == unicode:
00371           val1 = val1.encode('utf-8')
00372           length = len(val1)
00373         buff.write(struct.pack('<I%ss'%length, length, val1))
00374       length = len(self.result.grasp.pre_grasp_posture.position)
00375       buff.write(_struct_I.pack(length))
00376       pattern = '<%sd'%length
00377       buff.write(struct.pack(pattern, *self.result.grasp.pre_grasp_posture.position))
00378       length = len(self.result.grasp.pre_grasp_posture.velocity)
00379       buff.write(_struct_I.pack(length))
00380       pattern = '<%sd'%length
00381       buff.write(struct.pack(pattern, *self.result.grasp.pre_grasp_posture.velocity))
00382       length = len(self.result.grasp.pre_grasp_posture.effort)
00383       buff.write(_struct_I.pack(length))
00384       pattern = '<%sd'%length
00385       buff.write(struct.pack(pattern, *self.result.grasp.pre_grasp_posture.effort))
00386       _x = self
00387       buff.write(_struct_3I.pack(_x.result.grasp.grasp_posture.header.seq, _x.result.grasp.grasp_posture.header.stamp.secs, _x.result.grasp.grasp_posture.header.stamp.nsecs))
00388       _x = self.result.grasp.grasp_posture.header.frame_id
00389       length = len(_x)
00390       if python3 or type(_x) == unicode:
00391         _x = _x.encode('utf-8')
00392         length = len(_x)
00393       buff.write(struct.pack('<I%ss'%length, length, _x))
00394       length = len(self.result.grasp.grasp_posture.name)
00395       buff.write(_struct_I.pack(length))
00396       for val1 in self.result.grasp.grasp_posture.name:
00397         length = len(val1)
00398         if python3 or type(val1) == unicode:
00399           val1 = val1.encode('utf-8')
00400           length = len(val1)
00401         buff.write(struct.pack('<I%ss'%length, length, val1))
00402       length = len(self.result.grasp.grasp_posture.position)
00403       buff.write(_struct_I.pack(length))
00404       pattern = '<%sd'%length
00405       buff.write(struct.pack(pattern, *self.result.grasp.grasp_posture.position))
00406       length = len(self.result.grasp.grasp_posture.velocity)
00407       buff.write(_struct_I.pack(length))
00408       pattern = '<%sd'%length
00409       buff.write(struct.pack(pattern, *self.result.grasp.grasp_posture.velocity))
00410       length = len(self.result.grasp.grasp_posture.effort)
00411       buff.write(_struct_I.pack(length))
00412       pattern = '<%sd'%length
00413       buff.write(struct.pack(pattern, *self.result.grasp.grasp_posture.effort))
00414       _x = self
00415       buff.write(_struct_3I.pack(_x.result.grasp.grasp_pose.header.seq, _x.result.grasp.grasp_pose.header.stamp.secs, _x.result.grasp.grasp_pose.header.stamp.nsecs))
00416       _x = self.result.grasp.grasp_pose.header.frame_id
00417       length = len(_x)
00418       if python3 or type(_x) == unicode:
00419         _x = _x.encode('utf-8')
00420         length = len(_x)
00421       buff.write(struct.pack('<I%ss'%length, length, _x))
00422       _x = self
00423       buff.write(_struct_8d3I.pack(_x.result.grasp.grasp_pose.pose.position.x, _x.result.grasp.grasp_pose.pose.position.y, _x.result.grasp.grasp_pose.pose.position.z, _x.result.grasp.grasp_pose.pose.orientation.x, _x.result.grasp.grasp_pose.pose.orientation.y, _x.result.grasp.grasp_pose.pose.orientation.z, _x.result.grasp.grasp_pose.pose.orientation.w, _x.result.grasp.grasp_quality, _x.result.grasp.approach.direction.header.seq, _x.result.grasp.approach.direction.header.stamp.secs, _x.result.grasp.approach.direction.header.stamp.nsecs))
00424       _x = self.result.grasp.approach.direction.header.frame_id
00425       length = len(_x)
00426       if python3 or type(_x) == unicode:
00427         _x = _x.encode('utf-8')
00428         length = len(_x)
00429       buff.write(struct.pack('<I%ss'%length, length, _x))
00430       _x = self
00431       buff.write(_struct_3d2f3I.pack(_x.result.grasp.approach.direction.vector.x, _x.result.grasp.approach.direction.vector.y, _x.result.grasp.approach.direction.vector.z, _x.result.grasp.approach.desired_distance, _x.result.grasp.approach.min_distance, _x.result.grasp.retreat.direction.header.seq, _x.result.grasp.retreat.direction.header.stamp.secs, _x.result.grasp.retreat.direction.header.stamp.nsecs))
00432       _x = self.result.grasp.retreat.direction.header.frame_id
00433       length = len(_x)
00434       if python3 or type(_x) == unicode:
00435         _x = _x.encode('utf-8')
00436         length = len(_x)
00437       buff.write(struct.pack('<I%ss'%length, length, _x))
00438       _x = self
00439       buff.write(_struct_3d3f.pack(_x.result.grasp.retreat.direction.vector.x, _x.result.grasp.retreat.direction.vector.y, _x.result.grasp.retreat.direction.vector.z, _x.result.grasp.retreat.desired_distance, _x.result.grasp.retreat.min_distance, _x.result.grasp.max_contact_force))
00440       length = len(self.result.grasp.allowed_touch_objects)
00441       buff.write(_struct_I.pack(length))
00442       for val1 in self.result.grasp.allowed_touch_objects:
00443         length = len(val1)
00444         if python3 or type(val1) == unicode:
00445           val1 = val1.encode('utf-8')
00446           length = len(val1)
00447         buff.write(struct.pack('<I%ss'%length, length, val1))
00448       length = len(self.result.attempted_grasps)
00449       buff.write(_struct_I.pack(length))
00450       for val1 in self.result.attempted_grasps:
00451         _x = val1.id
00452         length = len(_x)
00453         if python3 or type(_x) == unicode:
00454           _x = _x.encode('utf-8')
00455           length = len(_x)
00456         buff.write(struct.pack('<I%ss'%length, length, _x))
00457         _v1 = val1.pre_grasp_posture
00458         _v2 = _v1.header
00459         buff.write(_struct_I.pack(_v2.seq))
00460         _v3 = _v2.stamp
00461         _x = _v3
00462         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00463         _x = _v2.frame_id
00464         length = len(_x)
00465         if python3 or type(_x) == unicode:
00466           _x = _x.encode('utf-8')
00467           length = len(_x)
00468         buff.write(struct.pack('<I%ss'%length, length, _x))
00469         length = len(_v1.name)
00470         buff.write(_struct_I.pack(length))
00471         for val3 in _v1.name:
00472           length = len(val3)
00473           if python3 or type(val3) == unicode:
00474             val3 = val3.encode('utf-8')
00475             length = len(val3)
00476           buff.write(struct.pack('<I%ss'%length, length, val3))
00477         length = len(_v1.position)
00478         buff.write(_struct_I.pack(length))
00479         pattern = '<%sd'%length
00480         buff.write(struct.pack(pattern, *_v1.position))
00481         length = len(_v1.velocity)
00482         buff.write(_struct_I.pack(length))
00483         pattern = '<%sd'%length
00484         buff.write(struct.pack(pattern, *_v1.velocity))
00485         length = len(_v1.effort)
00486         buff.write(_struct_I.pack(length))
00487         pattern = '<%sd'%length
00488         buff.write(struct.pack(pattern, *_v1.effort))
00489         _v4 = val1.grasp_posture
00490         _v5 = _v4.header
00491         buff.write(_struct_I.pack(_v5.seq))
00492         _v6 = _v5.stamp
00493         _x = _v6
00494         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00495         _x = _v5.frame_id
00496         length = len(_x)
00497         if python3 or type(_x) == unicode:
00498           _x = _x.encode('utf-8')
00499           length = len(_x)
00500         buff.write(struct.pack('<I%ss'%length, length, _x))
00501         length = len(_v4.name)
00502         buff.write(_struct_I.pack(length))
00503         for val3 in _v4.name:
00504           length = len(val3)
00505           if python3 or type(val3) == unicode:
00506             val3 = val3.encode('utf-8')
00507             length = len(val3)
00508           buff.write(struct.pack('<I%ss'%length, length, val3))
00509         length = len(_v4.position)
00510         buff.write(_struct_I.pack(length))
00511         pattern = '<%sd'%length
00512         buff.write(struct.pack(pattern, *_v4.position))
00513         length = len(_v4.velocity)
00514         buff.write(_struct_I.pack(length))
00515         pattern = '<%sd'%length
00516         buff.write(struct.pack(pattern, *_v4.velocity))
00517         length = len(_v4.effort)
00518         buff.write(_struct_I.pack(length))
00519         pattern = '<%sd'%length
00520         buff.write(struct.pack(pattern, *_v4.effort))
00521         _v7 = val1.grasp_pose
00522         _v8 = _v7.header
00523         buff.write(_struct_I.pack(_v8.seq))
00524         _v9 = _v8.stamp
00525         _x = _v9
00526         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00527         _x = _v8.frame_id
00528         length = len(_x)
00529         if python3 or type(_x) == unicode:
00530           _x = _x.encode('utf-8')
00531           length = len(_x)
00532         buff.write(struct.pack('<I%ss'%length, length, _x))
00533         _v10 = _v7.pose
00534         _v11 = _v10.position
00535         _x = _v11
00536         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00537         _v12 = _v10.orientation
00538         _x = _v12
00539         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00540         buff.write(_struct_d.pack(val1.grasp_quality))
00541         _v13 = val1.approach
00542         _v14 = _v13.direction
00543         _v15 = _v14.header
00544         buff.write(_struct_I.pack(_v15.seq))
00545         _v16 = _v15.stamp
00546         _x = _v16
00547         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00548         _x = _v15.frame_id
00549         length = len(_x)
00550         if python3 or type(_x) == unicode:
00551           _x = _x.encode('utf-8')
00552           length = len(_x)
00553         buff.write(struct.pack('<I%ss'%length, length, _x))
00554         _v17 = _v14.vector
00555         _x = _v17
00556         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00557         _x = _v13
00558         buff.write(_struct_2f.pack(_x.desired_distance, _x.min_distance))
00559         _v18 = val1.retreat
00560         _v19 = _v18.direction
00561         _v20 = _v19.header
00562         buff.write(_struct_I.pack(_v20.seq))
00563         _v21 = _v20.stamp
00564         _x = _v21
00565         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00566         _x = _v20.frame_id
00567         length = len(_x)
00568         if python3 or type(_x) == unicode:
00569           _x = _x.encode('utf-8')
00570           length = len(_x)
00571         buff.write(struct.pack('<I%ss'%length, length, _x))
00572         _v22 = _v19.vector
00573         _x = _v22
00574         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00575         _x = _v18
00576         buff.write(_struct_2f.pack(_x.desired_distance, _x.min_distance))
00577         buff.write(_struct_f.pack(val1.max_contact_force))
00578         length = len(val1.allowed_touch_objects)
00579         buff.write(_struct_I.pack(length))
00580         for val2 in val1.allowed_touch_objects:
00581           length = len(val2)
00582           if python3 or type(val2) == unicode:
00583             val2 = val2.encode('utf-8')
00584             length = len(val2)
00585           buff.write(struct.pack('<I%ss'%length, length, val2))
00586       length = len(self.result.attempted_grasp_results)
00587       buff.write(_struct_I.pack(length))
00588       for val1 in self.result.attempted_grasp_results:
00589         _x = val1
00590         buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
00591     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00592     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00593 
00594   def deserialize(self, str):
00595     """
00596     unpack serialized message in str into this message instance
00597     :param str: byte array of serialized message, ``str``
00598     """
00599     try:
00600       if self.header is None:
00601         self.header = std_msgs.msg.Header()
00602       if self.status is None:
00603         self.status = actionlib_msgs.msg.GoalStatus()
00604       if self.result is None:
00605         self.result = object_manipulation_msgs.msg.PickupResult()
00606       end = 0
00607       _x = self
00608       start = end
00609       end += 12
00610       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00611       start = end
00612       end += 4
00613       (length,) = _struct_I.unpack(str[start:end])
00614       start = end
00615       end += length
00616       if python3:
00617         self.header.frame_id = str[start:end].decode('utf-8')
00618       else:
00619         self.header.frame_id = str[start:end]
00620       _x = self
00621       start = end
00622       end += 8
00623       (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00624       start = end
00625       end += 4
00626       (length,) = _struct_I.unpack(str[start:end])
00627       start = end
00628       end += length
00629       if python3:
00630         self.status.goal_id.id = str[start:end].decode('utf-8')
00631       else:
00632         self.status.goal_id.id = str[start:end]
00633       start = end
00634       end += 1
00635       (self.status.status,) = _struct_B.unpack(str[start:end])
00636       start = end
00637       end += 4
00638       (length,) = _struct_I.unpack(str[start:end])
00639       start = end
00640       end += length
00641       if python3:
00642         self.status.text = str[start:end].decode('utf-8')
00643       else:
00644         self.status.text = str[start:end]
00645       start = end
00646       end += 4
00647       (self.result.manipulation_result.value,) = _struct_i.unpack(str[start:end])
00648       start = end
00649       end += 4
00650       (length,) = _struct_I.unpack(str[start:end])
00651       start = end
00652       end += length
00653       if python3:
00654         self.result.grasp.id = str[start:end].decode('utf-8')
00655       else:
00656         self.result.grasp.id = str[start:end]
00657       _x = self
00658       start = end
00659       end += 12
00660       (_x.result.grasp.pre_grasp_posture.header.seq, _x.result.grasp.pre_grasp_posture.header.stamp.secs, _x.result.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00661       start = end
00662       end += 4
00663       (length,) = _struct_I.unpack(str[start:end])
00664       start = end
00665       end += length
00666       if python3:
00667         self.result.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
00668       else:
00669         self.result.grasp.pre_grasp_posture.header.frame_id = str[start:end]
00670       start = end
00671       end += 4
00672       (length,) = _struct_I.unpack(str[start:end])
00673       self.result.grasp.pre_grasp_posture.name = []
00674       for i in range(0, length):
00675         start = end
00676         end += 4
00677         (length,) = _struct_I.unpack(str[start:end])
00678         start = end
00679         end += length
00680         if python3:
00681           val1 = str[start:end].decode('utf-8')
00682         else:
00683           val1 = str[start:end]
00684         self.result.grasp.pre_grasp_posture.name.append(val1)
00685       start = end
00686       end += 4
00687       (length,) = _struct_I.unpack(str[start:end])
00688       pattern = '<%sd'%length
00689       start = end
00690       end += struct.calcsize(pattern)
00691       self.result.grasp.pre_grasp_posture.position = struct.unpack(pattern, str[start:end])
00692       start = end
00693       end += 4
00694       (length,) = _struct_I.unpack(str[start:end])
00695       pattern = '<%sd'%length
00696       start = end
00697       end += struct.calcsize(pattern)
00698       self.result.grasp.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00699       start = end
00700       end += 4
00701       (length,) = _struct_I.unpack(str[start:end])
00702       pattern = '<%sd'%length
00703       start = end
00704       end += struct.calcsize(pattern)
00705       self.result.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end])
00706       _x = self
00707       start = end
00708       end += 12
00709       (_x.result.grasp.grasp_posture.header.seq, _x.result.grasp.grasp_posture.header.stamp.secs, _x.result.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00710       start = end
00711       end += 4
00712       (length,) = _struct_I.unpack(str[start:end])
00713       start = end
00714       end += length
00715       if python3:
00716         self.result.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
00717       else:
00718         self.result.grasp.grasp_posture.header.frame_id = str[start:end]
00719       start = end
00720       end += 4
00721       (length,) = _struct_I.unpack(str[start:end])
00722       self.result.grasp.grasp_posture.name = []
00723       for i in range(0, length):
00724         start = end
00725         end += 4
00726         (length,) = _struct_I.unpack(str[start:end])
00727         start = end
00728         end += length
00729         if python3:
00730           val1 = str[start:end].decode('utf-8')
00731         else:
00732           val1 = str[start:end]
00733         self.result.grasp.grasp_posture.name.append(val1)
00734       start = end
00735       end += 4
00736       (length,) = _struct_I.unpack(str[start:end])
00737       pattern = '<%sd'%length
00738       start = end
00739       end += struct.calcsize(pattern)
00740       self.result.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end])
00741       start = end
00742       end += 4
00743       (length,) = _struct_I.unpack(str[start:end])
00744       pattern = '<%sd'%length
00745       start = end
00746       end += struct.calcsize(pattern)
00747       self.result.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00748       start = end
00749       end += 4
00750       (length,) = _struct_I.unpack(str[start:end])
00751       pattern = '<%sd'%length
00752       start = end
00753       end += struct.calcsize(pattern)
00754       self.result.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end])
00755       _x = self
00756       start = end
00757       end += 12
00758       (_x.result.grasp.grasp_pose.header.seq, _x.result.grasp.grasp_pose.header.stamp.secs, _x.result.grasp.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00759       start = end
00760       end += 4
00761       (length,) = _struct_I.unpack(str[start:end])
00762       start = end
00763       end += length
00764       if python3:
00765         self.result.grasp.grasp_pose.header.frame_id = str[start:end].decode('utf-8')
00766       else:
00767         self.result.grasp.grasp_pose.header.frame_id = str[start:end]
00768       _x = self
00769       start = end
00770       end += 76
00771       (_x.result.grasp.grasp_pose.pose.position.x, _x.result.grasp.grasp_pose.pose.position.y, _x.result.grasp.grasp_pose.pose.position.z, _x.result.grasp.grasp_pose.pose.orientation.x, _x.result.grasp.grasp_pose.pose.orientation.y, _x.result.grasp.grasp_pose.pose.orientation.z, _x.result.grasp.grasp_pose.pose.orientation.w, _x.result.grasp.grasp_quality, _x.result.grasp.approach.direction.header.seq, _x.result.grasp.approach.direction.header.stamp.secs, _x.result.grasp.approach.direction.header.stamp.nsecs,) = _struct_8d3I.unpack(str[start:end])
00772       start = end
00773       end += 4
00774       (length,) = _struct_I.unpack(str[start:end])
00775       start = end
00776       end += length
00777       if python3:
00778         self.result.grasp.approach.direction.header.frame_id = str[start:end].decode('utf-8')
00779       else:
00780         self.result.grasp.approach.direction.header.frame_id = str[start:end]
00781       _x = self
00782       start = end
00783       end += 44
00784       (_x.result.grasp.approach.direction.vector.x, _x.result.grasp.approach.direction.vector.y, _x.result.grasp.approach.direction.vector.z, _x.result.grasp.approach.desired_distance, _x.result.grasp.approach.min_distance, _x.result.grasp.retreat.direction.header.seq, _x.result.grasp.retreat.direction.header.stamp.secs, _x.result.grasp.retreat.direction.header.stamp.nsecs,) = _struct_3d2f3I.unpack(str[start:end])
00785       start = end
00786       end += 4
00787       (length,) = _struct_I.unpack(str[start:end])
00788       start = end
00789       end += length
00790       if python3:
00791         self.result.grasp.retreat.direction.header.frame_id = str[start:end].decode('utf-8')
00792       else:
00793         self.result.grasp.retreat.direction.header.frame_id = str[start:end]
00794       _x = self
00795       start = end
00796       end += 36
00797       (_x.result.grasp.retreat.direction.vector.x, _x.result.grasp.retreat.direction.vector.y, _x.result.grasp.retreat.direction.vector.z, _x.result.grasp.retreat.desired_distance, _x.result.grasp.retreat.min_distance, _x.result.grasp.max_contact_force,) = _struct_3d3f.unpack(str[start:end])
00798       start = end
00799       end += 4
00800       (length,) = _struct_I.unpack(str[start:end])
00801       self.result.grasp.allowed_touch_objects = []
00802       for i in range(0, length):
00803         start = end
00804         end += 4
00805         (length,) = _struct_I.unpack(str[start:end])
00806         start = end
00807         end += length
00808         if python3:
00809           val1 = str[start:end].decode('utf-8')
00810         else:
00811           val1 = str[start:end]
00812         self.result.grasp.allowed_touch_objects.append(val1)
00813       start = end
00814       end += 4
00815       (length,) = _struct_I.unpack(str[start:end])
00816       self.result.attempted_grasps = []
00817       for i in range(0, length):
00818         val1 = manipulation_msgs.msg.Grasp()
00819         start = end
00820         end += 4
00821         (length,) = _struct_I.unpack(str[start:end])
00822         start = end
00823         end += length
00824         if python3:
00825           val1.id = str[start:end].decode('utf-8')
00826         else:
00827           val1.id = str[start:end]
00828         _v23 = val1.pre_grasp_posture
00829         _v24 = _v23.header
00830         start = end
00831         end += 4
00832         (_v24.seq,) = _struct_I.unpack(str[start:end])
00833         _v25 = _v24.stamp
00834         _x = _v25
00835         start = end
00836         end += 8
00837         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00838         start = end
00839         end += 4
00840         (length,) = _struct_I.unpack(str[start:end])
00841         start = end
00842         end += length
00843         if python3:
00844           _v24.frame_id = str[start:end].decode('utf-8')
00845         else:
00846           _v24.frame_id = str[start:end]
00847         start = end
00848         end += 4
00849         (length,) = _struct_I.unpack(str[start:end])
00850         _v23.name = []
00851         for i in range(0, length):
00852           start = end
00853           end += 4
00854           (length,) = _struct_I.unpack(str[start:end])
00855           start = end
00856           end += length
00857           if python3:
00858             val3 = str[start:end].decode('utf-8')
00859           else:
00860             val3 = str[start:end]
00861           _v23.name.append(val3)
00862         start = end
00863         end += 4
00864         (length,) = _struct_I.unpack(str[start:end])
00865         pattern = '<%sd'%length
00866         start = end
00867         end += struct.calcsize(pattern)
00868         _v23.position = struct.unpack(pattern, str[start:end])
00869         start = end
00870         end += 4
00871         (length,) = _struct_I.unpack(str[start:end])
00872         pattern = '<%sd'%length
00873         start = end
00874         end += struct.calcsize(pattern)
00875         _v23.velocity = struct.unpack(pattern, str[start:end])
00876         start = end
00877         end += 4
00878         (length,) = _struct_I.unpack(str[start:end])
00879         pattern = '<%sd'%length
00880         start = end
00881         end += struct.calcsize(pattern)
00882         _v23.effort = struct.unpack(pattern, str[start:end])
00883         _v26 = val1.grasp_posture
00884         _v27 = _v26.header
00885         start = end
00886         end += 4
00887         (_v27.seq,) = _struct_I.unpack(str[start:end])
00888         _v28 = _v27.stamp
00889         _x = _v28
00890         start = end
00891         end += 8
00892         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00893         start = end
00894         end += 4
00895         (length,) = _struct_I.unpack(str[start:end])
00896         start = end
00897         end += length
00898         if python3:
00899           _v27.frame_id = str[start:end].decode('utf-8')
00900         else:
00901           _v27.frame_id = str[start:end]
00902         start = end
00903         end += 4
00904         (length,) = _struct_I.unpack(str[start:end])
00905         _v26.name = []
00906         for i in range(0, length):
00907           start = end
00908           end += 4
00909           (length,) = _struct_I.unpack(str[start:end])
00910           start = end
00911           end += length
00912           if python3:
00913             val3 = str[start:end].decode('utf-8')
00914           else:
00915             val3 = str[start:end]
00916           _v26.name.append(val3)
00917         start = end
00918         end += 4
00919         (length,) = _struct_I.unpack(str[start:end])
00920         pattern = '<%sd'%length
00921         start = end
00922         end += struct.calcsize(pattern)
00923         _v26.position = struct.unpack(pattern, str[start:end])
00924         start = end
00925         end += 4
00926         (length,) = _struct_I.unpack(str[start:end])
00927         pattern = '<%sd'%length
00928         start = end
00929         end += struct.calcsize(pattern)
00930         _v26.velocity = struct.unpack(pattern, str[start:end])
00931         start = end
00932         end += 4
00933         (length,) = _struct_I.unpack(str[start:end])
00934         pattern = '<%sd'%length
00935         start = end
00936         end += struct.calcsize(pattern)
00937         _v26.effort = struct.unpack(pattern, str[start:end])
00938         _v29 = val1.grasp_pose
00939         _v30 = _v29.header
00940         start = end
00941         end += 4
00942         (_v30.seq,) = _struct_I.unpack(str[start:end])
00943         _v31 = _v30.stamp
00944         _x = _v31
00945         start = end
00946         end += 8
00947         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00948         start = end
00949         end += 4
00950         (length,) = _struct_I.unpack(str[start:end])
00951         start = end
00952         end += length
00953         if python3:
00954           _v30.frame_id = str[start:end].decode('utf-8')
00955         else:
00956           _v30.frame_id = str[start:end]
00957         _v32 = _v29.pose
00958         _v33 = _v32.position
00959         _x = _v33
00960         start = end
00961         end += 24
00962         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00963         _v34 = _v32.orientation
00964         _x = _v34
00965         start = end
00966         end += 32
00967         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00968         start = end
00969         end += 8
00970         (val1.grasp_quality,) = _struct_d.unpack(str[start:end])
00971         _v35 = val1.approach
00972         _v36 = _v35.direction
00973         _v37 = _v36.header
00974         start = end
00975         end += 4
00976         (_v37.seq,) = _struct_I.unpack(str[start:end])
00977         _v38 = _v37.stamp
00978         _x = _v38
00979         start = end
00980         end += 8
00981         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00982         start = end
00983         end += 4
00984         (length,) = _struct_I.unpack(str[start:end])
00985         start = end
00986         end += length
00987         if python3:
00988           _v37.frame_id = str[start:end].decode('utf-8')
00989         else:
00990           _v37.frame_id = str[start:end]
00991         _v39 = _v36.vector
00992         _x = _v39
00993         start = end
00994         end += 24
00995         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00996         _x = _v35
00997         start = end
00998         end += 8
00999         (_x.desired_distance, _x.min_distance,) = _struct_2f.unpack(str[start:end])
01000         _v40 = val1.retreat
01001         _v41 = _v40.direction
01002         _v42 = _v41.header
01003         start = end
01004         end += 4
01005         (_v42.seq,) = _struct_I.unpack(str[start:end])
01006         _v43 = _v42.stamp
01007         _x = _v43
01008         start = end
01009         end += 8
01010         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01011         start = end
01012         end += 4
01013         (length,) = _struct_I.unpack(str[start:end])
01014         start = end
01015         end += length
01016         if python3:
01017           _v42.frame_id = str[start:end].decode('utf-8')
01018         else:
01019           _v42.frame_id = str[start:end]
01020         _v44 = _v41.vector
01021         _x = _v44
01022         start = end
01023         end += 24
01024         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01025         _x = _v40
01026         start = end
01027         end += 8
01028         (_x.desired_distance, _x.min_distance,) = _struct_2f.unpack(str[start:end])
01029         start = end
01030         end += 4
01031         (val1.max_contact_force,) = _struct_f.unpack(str[start:end])
01032         start = end
01033         end += 4
01034         (length,) = _struct_I.unpack(str[start:end])
01035         val1.allowed_touch_objects = []
01036         for i in range(0, length):
01037           start = end
01038           end += 4
01039           (length,) = _struct_I.unpack(str[start:end])
01040           start = end
01041           end += length
01042           if python3:
01043             val2 = str[start:end].decode('utf-8')
01044           else:
01045             val2 = str[start:end]
01046           val1.allowed_touch_objects.append(val2)
01047         self.result.attempted_grasps.append(val1)
01048       start = end
01049       end += 4
01050       (length,) = _struct_I.unpack(str[start:end])
01051       self.result.attempted_grasp_results = []
01052       for i in range(0, length):
01053         val1 = object_manipulation_msgs.msg.GraspResult()
01054         _x = val1
01055         start = end
01056         end += 5
01057         (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
01058         val1.continuation_possible = bool(val1.continuation_possible)
01059         self.result.attempted_grasp_results.append(val1)
01060       return self
01061     except struct.error as e:
01062       raise genpy.DeserializationError(e) #most likely buffer underfill
01063 
01064 
01065   def serialize_numpy(self, buff, numpy):
01066     """
01067     serialize message with numpy array types into buffer
01068     :param buff: buffer, ``StringIO``
01069     :param numpy: numpy python module
01070     """
01071     try:
01072       _x = self
01073       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
01074       _x = self.header.frame_id
01075       length = len(_x)
01076       if python3 or type(_x) == unicode:
01077         _x = _x.encode('utf-8')
01078         length = len(_x)
01079       buff.write(struct.pack('<I%ss'%length, length, _x))
01080       _x = self
01081       buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
01082       _x = self.status.goal_id.id
01083       length = len(_x)
01084       if python3 or type(_x) == unicode:
01085         _x = _x.encode('utf-8')
01086         length = len(_x)
01087       buff.write(struct.pack('<I%ss'%length, length, _x))
01088       buff.write(_struct_B.pack(self.status.status))
01089       _x = self.status.text
01090       length = len(_x)
01091       if python3 or type(_x) == unicode:
01092         _x = _x.encode('utf-8')
01093         length = len(_x)
01094       buff.write(struct.pack('<I%ss'%length, length, _x))
01095       buff.write(_struct_i.pack(self.result.manipulation_result.value))
01096       _x = self.result.grasp.id
01097       length = len(_x)
01098       if python3 or type(_x) == unicode:
01099         _x = _x.encode('utf-8')
01100         length = len(_x)
01101       buff.write(struct.pack('<I%ss'%length, length, _x))
01102       _x = self
01103       buff.write(_struct_3I.pack(_x.result.grasp.pre_grasp_posture.header.seq, _x.result.grasp.pre_grasp_posture.header.stamp.secs, _x.result.grasp.pre_grasp_posture.header.stamp.nsecs))
01104       _x = self.result.grasp.pre_grasp_posture.header.frame_id
01105       length = len(_x)
01106       if python3 or type(_x) == unicode:
01107         _x = _x.encode('utf-8')
01108         length = len(_x)
01109       buff.write(struct.pack('<I%ss'%length, length, _x))
01110       length = len(self.result.grasp.pre_grasp_posture.name)
01111       buff.write(_struct_I.pack(length))
01112       for val1 in self.result.grasp.pre_grasp_posture.name:
01113         length = len(val1)
01114         if python3 or type(val1) == unicode:
01115           val1 = val1.encode('utf-8')
01116           length = len(val1)
01117         buff.write(struct.pack('<I%ss'%length, length, val1))
01118       length = len(self.result.grasp.pre_grasp_posture.position)
01119       buff.write(_struct_I.pack(length))
01120       pattern = '<%sd'%length
01121       buff.write(self.result.grasp.pre_grasp_posture.position.tostring())
01122       length = len(self.result.grasp.pre_grasp_posture.velocity)
01123       buff.write(_struct_I.pack(length))
01124       pattern = '<%sd'%length
01125       buff.write(self.result.grasp.pre_grasp_posture.velocity.tostring())
01126       length = len(self.result.grasp.pre_grasp_posture.effort)
01127       buff.write(_struct_I.pack(length))
01128       pattern = '<%sd'%length
01129       buff.write(self.result.grasp.pre_grasp_posture.effort.tostring())
01130       _x = self
01131       buff.write(_struct_3I.pack(_x.result.grasp.grasp_posture.header.seq, _x.result.grasp.grasp_posture.header.stamp.secs, _x.result.grasp.grasp_posture.header.stamp.nsecs))
01132       _x = self.result.grasp.grasp_posture.header.frame_id
01133       length = len(_x)
01134       if python3 or type(_x) == unicode:
01135         _x = _x.encode('utf-8')
01136         length = len(_x)
01137       buff.write(struct.pack('<I%ss'%length, length, _x))
01138       length = len(self.result.grasp.grasp_posture.name)
01139       buff.write(_struct_I.pack(length))
01140       for val1 in self.result.grasp.grasp_posture.name:
01141         length = len(val1)
01142         if python3 or type(val1) == unicode:
01143           val1 = val1.encode('utf-8')
01144           length = len(val1)
01145         buff.write(struct.pack('<I%ss'%length, length, val1))
01146       length = len(self.result.grasp.grasp_posture.position)
01147       buff.write(_struct_I.pack(length))
01148       pattern = '<%sd'%length
01149       buff.write(self.result.grasp.grasp_posture.position.tostring())
01150       length = len(self.result.grasp.grasp_posture.velocity)
01151       buff.write(_struct_I.pack(length))
01152       pattern = '<%sd'%length
01153       buff.write(self.result.grasp.grasp_posture.velocity.tostring())
01154       length = len(self.result.grasp.grasp_posture.effort)
01155       buff.write(_struct_I.pack(length))
01156       pattern = '<%sd'%length
01157       buff.write(self.result.grasp.grasp_posture.effort.tostring())
01158       _x = self
01159       buff.write(_struct_3I.pack(_x.result.grasp.grasp_pose.header.seq, _x.result.grasp.grasp_pose.header.stamp.secs, _x.result.grasp.grasp_pose.header.stamp.nsecs))
01160       _x = self.result.grasp.grasp_pose.header.frame_id
01161       length = len(_x)
01162       if python3 or type(_x) == unicode:
01163         _x = _x.encode('utf-8')
01164         length = len(_x)
01165       buff.write(struct.pack('<I%ss'%length, length, _x))
01166       _x = self
01167       buff.write(_struct_8d3I.pack(_x.result.grasp.grasp_pose.pose.position.x, _x.result.grasp.grasp_pose.pose.position.y, _x.result.grasp.grasp_pose.pose.position.z, _x.result.grasp.grasp_pose.pose.orientation.x, _x.result.grasp.grasp_pose.pose.orientation.y, _x.result.grasp.grasp_pose.pose.orientation.z, _x.result.grasp.grasp_pose.pose.orientation.w, _x.result.grasp.grasp_quality, _x.result.grasp.approach.direction.header.seq, _x.result.grasp.approach.direction.header.stamp.secs, _x.result.grasp.approach.direction.header.stamp.nsecs))
01168       _x = self.result.grasp.approach.direction.header.frame_id
01169       length = len(_x)
01170       if python3 or type(_x) == unicode:
01171         _x = _x.encode('utf-8')
01172         length = len(_x)
01173       buff.write(struct.pack('<I%ss'%length, length, _x))
01174       _x = self
01175       buff.write(_struct_3d2f3I.pack(_x.result.grasp.approach.direction.vector.x, _x.result.grasp.approach.direction.vector.y, _x.result.grasp.approach.direction.vector.z, _x.result.grasp.approach.desired_distance, _x.result.grasp.approach.min_distance, _x.result.grasp.retreat.direction.header.seq, _x.result.grasp.retreat.direction.header.stamp.secs, _x.result.grasp.retreat.direction.header.stamp.nsecs))
01176       _x = self.result.grasp.retreat.direction.header.frame_id
01177       length = len(_x)
01178       if python3 or type(_x) == unicode:
01179         _x = _x.encode('utf-8')
01180         length = len(_x)
01181       buff.write(struct.pack('<I%ss'%length, length, _x))
01182       _x = self
01183       buff.write(_struct_3d3f.pack(_x.result.grasp.retreat.direction.vector.x, _x.result.grasp.retreat.direction.vector.y, _x.result.grasp.retreat.direction.vector.z, _x.result.grasp.retreat.desired_distance, _x.result.grasp.retreat.min_distance, _x.result.grasp.max_contact_force))
01184       length = len(self.result.grasp.allowed_touch_objects)
01185       buff.write(_struct_I.pack(length))
01186       for val1 in self.result.grasp.allowed_touch_objects:
01187         length = len(val1)
01188         if python3 or type(val1) == unicode:
01189           val1 = val1.encode('utf-8')
01190           length = len(val1)
01191         buff.write(struct.pack('<I%ss'%length, length, val1))
01192       length = len(self.result.attempted_grasps)
01193       buff.write(_struct_I.pack(length))
01194       for val1 in self.result.attempted_grasps:
01195         _x = val1.id
01196         length = len(_x)
01197         if python3 or type(_x) == unicode:
01198           _x = _x.encode('utf-8')
01199           length = len(_x)
01200         buff.write(struct.pack('<I%ss'%length, length, _x))
01201         _v45 = val1.pre_grasp_posture
01202         _v46 = _v45.header
01203         buff.write(_struct_I.pack(_v46.seq))
01204         _v47 = _v46.stamp
01205         _x = _v47
01206         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01207         _x = _v46.frame_id
01208         length = len(_x)
01209         if python3 or type(_x) == unicode:
01210           _x = _x.encode('utf-8')
01211           length = len(_x)
01212         buff.write(struct.pack('<I%ss'%length, length, _x))
01213         length = len(_v45.name)
01214         buff.write(_struct_I.pack(length))
01215         for val3 in _v45.name:
01216           length = len(val3)
01217           if python3 or type(val3) == unicode:
01218             val3 = val3.encode('utf-8')
01219             length = len(val3)
01220           buff.write(struct.pack('<I%ss'%length, length, val3))
01221         length = len(_v45.position)
01222         buff.write(_struct_I.pack(length))
01223         pattern = '<%sd'%length
01224         buff.write(_v45.position.tostring())
01225         length = len(_v45.velocity)
01226         buff.write(_struct_I.pack(length))
01227         pattern = '<%sd'%length
01228         buff.write(_v45.velocity.tostring())
01229         length = len(_v45.effort)
01230         buff.write(_struct_I.pack(length))
01231         pattern = '<%sd'%length
01232         buff.write(_v45.effort.tostring())
01233         _v48 = val1.grasp_posture
01234         _v49 = _v48.header
01235         buff.write(_struct_I.pack(_v49.seq))
01236         _v50 = _v49.stamp
01237         _x = _v50
01238         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01239         _x = _v49.frame_id
01240         length = len(_x)
01241         if python3 or type(_x) == unicode:
01242           _x = _x.encode('utf-8')
01243           length = len(_x)
01244         buff.write(struct.pack('<I%ss'%length, length, _x))
01245         length = len(_v48.name)
01246         buff.write(_struct_I.pack(length))
01247         for val3 in _v48.name:
01248           length = len(val3)
01249           if python3 or type(val3) == unicode:
01250             val3 = val3.encode('utf-8')
01251             length = len(val3)
01252           buff.write(struct.pack('<I%ss'%length, length, val3))
01253         length = len(_v48.position)
01254         buff.write(_struct_I.pack(length))
01255         pattern = '<%sd'%length
01256         buff.write(_v48.position.tostring())
01257         length = len(_v48.velocity)
01258         buff.write(_struct_I.pack(length))
01259         pattern = '<%sd'%length
01260         buff.write(_v48.velocity.tostring())
01261         length = len(_v48.effort)
01262         buff.write(_struct_I.pack(length))
01263         pattern = '<%sd'%length
01264         buff.write(_v48.effort.tostring())
01265         _v51 = val1.grasp_pose
01266         _v52 = _v51.header
01267         buff.write(_struct_I.pack(_v52.seq))
01268         _v53 = _v52.stamp
01269         _x = _v53
01270         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01271         _x = _v52.frame_id
01272         length = len(_x)
01273         if python3 or type(_x) == unicode:
01274           _x = _x.encode('utf-8')
01275           length = len(_x)
01276         buff.write(struct.pack('<I%ss'%length, length, _x))
01277         _v54 = _v51.pose
01278         _v55 = _v54.position
01279         _x = _v55
01280         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01281         _v56 = _v54.orientation
01282         _x = _v56
01283         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01284         buff.write(_struct_d.pack(val1.grasp_quality))
01285         _v57 = val1.approach
01286         _v58 = _v57.direction
01287         _v59 = _v58.header
01288         buff.write(_struct_I.pack(_v59.seq))
01289         _v60 = _v59.stamp
01290         _x = _v60
01291         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01292         _x = _v59.frame_id
01293         length = len(_x)
01294         if python3 or type(_x) == unicode:
01295           _x = _x.encode('utf-8')
01296           length = len(_x)
01297         buff.write(struct.pack('<I%ss'%length, length, _x))
01298         _v61 = _v58.vector
01299         _x = _v61
01300         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01301         _x = _v57
01302         buff.write(_struct_2f.pack(_x.desired_distance, _x.min_distance))
01303         _v62 = val1.retreat
01304         _v63 = _v62.direction
01305         _v64 = _v63.header
01306         buff.write(_struct_I.pack(_v64.seq))
01307         _v65 = _v64.stamp
01308         _x = _v65
01309         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01310         _x = _v64.frame_id
01311         length = len(_x)
01312         if python3 or type(_x) == unicode:
01313           _x = _x.encode('utf-8')
01314           length = len(_x)
01315         buff.write(struct.pack('<I%ss'%length, length, _x))
01316         _v66 = _v63.vector
01317         _x = _v66
01318         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01319         _x = _v62
01320         buff.write(_struct_2f.pack(_x.desired_distance, _x.min_distance))
01321         buff.write(_struct_f.pack(val1.max_contact_force))
01322         length = len(val1.allowed_touch_objects)
01323         buff.write(_struct_I.pack(length))
01324         for val2 in val1.allowed_touch_objects:
01325           length = len(val2)
01326           if python3 or type(val2) == unicode:
01327             val2 = val2.encode('utf-8')
01328             length = len(val2)
01329           buff.write(struct.pack('<I%ss'%length, length, val2))
01330       length = len(self.result.attempted_grasp_results)
01331       buff.write(_struct_I.pack(length))
01332       for val1 in self.result.attempted_grasp_results:
01333         _x = val1
01334         buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
01335     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
01336     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
01337 
01338   def deserialize_numpy(self, str, numpy):
01339     """
01340     unpack serialized message in str into this message instance using numpy for array types
01341     :param str: byte array of serialized message, ``str``
01342     :param numpy: numpy python module
01343     """
01344     try:
01345       if self.header is None:
01346         self.header = std_msgs.msg.Header()
01347       if self.status is None:
01348         self.status = actionlib_msgs.msg.GoalStatus()
01349       if self.result is None:
01350         self.result = object_manipulation_msgs.msg.PickupResult()
01351       end = 0
01352       _x = self
01353       start = end
01354       end += 12
01355       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01356       start = end
01357       end += 4
01358       (length,) = _struct_I.unpack(str[start:end])
01359       start = end
01360       end += length
01361       if python3:
01362         self.header.frame_id = str[start:end].decode('utf-8')
01363       else:
01364         self.header.frame_id = str[start:end]
01365       _x = self
01366       start = end
01367       end += 8
01368       (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01369       start = end
01370       end += 4
01371       (length,) = _struct_I.unpack(str[start:end])
01372       start = end
01373       end += length
01374       if python3:
01375         self.status.goal_id.id = str[start:end].decode('utf-8')
01376       else:
01377         self.status.goal_id.id = str[start:end]
01378       start = end
01379       end += 1
01380       (self.status.status,) = _struct_B.unpack(str[start:end])
01381       start = end
01382       end += 4
01383       (length,) = _struct_I.unpack(str[start:end])
01384       start = end
01385       end += length
01386       if python3:
01387         self.status.text = str[start:end].decode('utf-8')
01388       else:
01389         self.status.text = str[start:end]
01390       start = end
01391       end += 4
01392       (self.result.manipulation_result.value,) = _struct_i.unpack(str[start:end])
01393       start = end
01394       end += 4
01395       (length,) = _struct_I.unpack(str[start:end])
01396       start = end
01397       end += length
01398       if python3:
01399         self.result.grasp.id = str[start:end].decode('utf-8')
01400       else:
01401         self.result.grasp.id = str[start:end]
01402       _x = self
01403       start = end
01404       end += 12
01405       (_x.result.grasp.pre_grasp_posture.header.seq, _x.result.grasp.pre_grasp_posture.header.stamp.secs, _x.result.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01406       start = end
01407       end += 4
01408       (length,) = _struct_I.unpack(str[start:end])
01409       start = end
01410       end += length
01411       if python3:
01412         self.result.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
01413       else:
01414         self.result.grasp.pre_grasp_posture.header.frame_id = str[start:end]
01415       start = end
01416       end += 4
01417       (length,) = _struct_I.unpack(str[start:end])
01418       self.result.grasp.pre_grasp_posture.name = []
01419       for i in range(0, length):
01420         start = end
01421         end += 4
01422         (length,) = _struct_I.unpack(str[start:end])
01423         start = end
01424         end += length
01425         if python3:
01426           val1 = str[start:end].decode('utf-8')
01427         else:
01428           val1 = str[start:end]
01429         self.result.grasp.pre_grasp_posture.name.append(val1)
01430       start = end
01431       end += 4
01432       (length,) = _struct_I.unpack(str[start:end])
01433       pattern = '<%sd'%length
01434       start = end
01435       end += struct.calcsize(pattern)
01436       self.result.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01437       start = end
01438       end += 4
01439       (length,) = _struct_I.unpack(str[start:end])
01440       pattern = '<%sd'%length
01441       start = end
01442       end += struct.calcsize(pattern)
01443       self.result.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01444       start = end
01445       end += 4
01446       (length,) = _struct_I.unpack(str[start:end])
01447       pattern = '<%sd'%length
01448       start = end
01449       end += struct.calcsize(pattern)
01450       self.result.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01451       _x = self
01452       start = end
01453       end += 12
01454       (_x.result.grasp.grasp_posture.header.seq, _x.result.grasp.grasp_posture.header.stamp.secs, _x.result.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01455       start = end
01456       end += 4
01457       (length,) = _struct_I.unpack(str[start:end])
01458       start = end
01459       end += length
01460       if python3:
01461         self.result.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
01462       else:
01463         self.result.grasp.grasp_posture.header.frame_id = str[start:end]
01464       start = end
01465       end += 4
01466       (length,) = _struct_I.unpack(str[start:end])
01467       self.result.grasp.grasp_posture.name = []
01468       for i in range(0, length):
01469         start = end
01470         end += 4
01471         (length,) = _struct_I.unpack(str[start:end])
01472         start = end
01473         end += length
01474         if python3:
01475           val1 = str[start:end].decode('utf-8')
01476         else:
01477           val1 = str[start:end]
01478         self.result.grasp.grasp_posture.name.append(val1)
01479       start = end
01480       end += 4
01481       (length,) = _struct_I.unpack(str[start:end])
01482       pattern = '<%sd'%length
01483       start = end
01484       end += struct.calcsize(pattern)
01485       self.result.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01486       start = end
01487       end += 4
01488       (length,) = _struct_I.unpack(str[start:end])
01489       pattern = '<%sd'%length
01490       start = end
01491       end += struct.calcsize(pattern)
01492       self.result.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01493       start = end
01494       end += 4
01495       (length,) = _struct_I.unpack(str[start:end])
01496       pattern = '<%sd'%length
01497       start = end
01498       end += struct.calcsize(pattern)
01499       self.result.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01500       _x = self
01501       start = end
01502       end += 12
01503       (_x.result.grasp.grasp_pose.header.seq, _x.result.grasp.grasp_pose.header.stamp.secs, _x.result.grasp.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01504       start = end
01505       end += 4
01506       (length,) = _struct_I.unpack(str[start:end])
01507       start = end
01508       end += length
01509       if python3:
01510         self.result.grasp.grasp_pose.header.frame_id = str[start:end].decode('utf-8')
01511       else:
01512         self.result.grasp.grasp_pose.header.frame_id = str[start:end]
01513       _x = self
01514       start = end
01515       end += 76
01516       (_x.result.grasp.grasp_pose.pose.position.x, _x.result.grasp.grasp_pose.pose.position.y, _x.result.grasp.grasp_pose.pose.position.z, _x.result.grasp.grasp_pose.pose.orientation.x, _x.result.grasp.grasp_pose.pose.orientation.y, _x.result.grasp.grasp_pose.pose.orientation.z, _x.result.grasp.grasp_pose.pose.orientation.w, _x.result.grasp.grasp_quality, _x.result.grasp.approach.direction.header.seq, _x.result.grasp.approach.direction.header.stamp.secs, _x.result.grasp.approach.direction.header.stamp.nsecs,) = _struct_8d3I.unpack(str[start:end])
01517       start = end
01518       end += 4
01519       (length,) = _struct_I.unpack(str[start:end])
01520       start = end
01521       end += length
01522       if python3:
01523         self.result.grasp.approach.direction.header.frame_id = str[start:end].decode('utf-8')
01524       else:
01525         self.result.grasp.approach.direction.header.frame_id = str[start:end]
01526       _x = self
01527       start = end
01528       end += 44
01529       (_x.result.grasp.approach.direction.vector.x, _x.result.grasp.approach.direction.vector.y, _x.result.grasp.approach.direction.vector.z, _x.result.grasp.approach.desired_distance, _x.result.grasp.approach.min_distance, _x.result.grasp.retreat.direction.header.seq, _x.result.grasp.retreat.direction.header.stamp.secs, _x.result.grasp.retreat.direction.header.stamp.nsecs,) = _struct_3d2f3I.unpack(str[start:end])
01530       start = end
01531       end += 4
01532       (length,) = _struct_I.unpack(str[start:end])
01533       start = end
01534       end += length
01535       if python3:
01536         self.result.grasp.retreat.direction.header.frame_id = str[start:end].decode('utf-8')
01537       else:
01538         self.result.grasp.retreat.direction.header.frame_id = str[start:end]
01539       _x = self
01540       start = end
01541       end += 36
01542       (_x.result.grasp.retreat.direction.vector.x, _x.result.grasp.retreat.direction.vector.y, _x.result.grasp.retreat.direction.vector.z, _x.result.grasp.retreat.desired_distance, _x.result.grasp.retreat.min_distance, _x.result.grasp.max_contact_force,) = _struct_3d3f.unpack(str[start:end])
01543       start = end
01544       end += 4
01545       (length,) = _struct_I.unpack(str[start:end])
01546       self.result.grasp.allowed_touch_objects = []
01547       for i in range(0, length):
01548         start = end
01549         end += 4
01550         (length,) = _struct_I.unpack(str[start:end])
01551         start = end
01552         end += length
01553         if python3:
01554           val1 = str[start:end].decode('utf-8')
01555         else:
01556           val1 = str[start:end]
01557         self.result.grasp.allowed_touch_objects.append(val1)
01558       start = end
01559       end += 4
01560       (length,) = _struct_I.unpack(str[start:end])
01561       self.result.attempted_grasps = []
01562       for i in range(0, length):
01563         val1 = manipulation_msgs.msg.Grasp()
01564         start = end
01565         end += 4
01566         (length,) = _struct_I.unpack(str[start:end])
01567         start = end
01568         end += length
01569         if python3:
01570           val1.id = str[start:end].decode('utf-8')
01571         else:
01572           val1.id = str[start:end]
01573         _v67 = val1.pre_grasp_posture
01574         _v68 = _v67.header
01575         start = end
01576         end += 4
01577         (_v68.seq,) = _struct_I.unpack(str[start:end])
01578         _v69 = _v68.stamp
01579         _x = _v69
01580         start = end
01581         end += 8
01582         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01583         start = end
01584         end += 4
01585         (length,) = _struct_I.unpack(str[start:end])
01586         start = end
01587         end += length
01588         if python3:
01589           _v68.frame_id = str[start:end].decode('utf-8')
01590         else:
01591           _v68.frame_id = str[start:end]
01592         start = end
01593         end += 4
01594         (length,) = _struct_I.unpack(str[start:end])
01595         _v67.name = []
01596         for i in range(0, length):
01597           start = end
01598           end += 4
01599           (length,) = _struct_I.unpack(str[start:end])
01600           start = end
01601           end += length
01602           if python3:
01603             val3 = str[start:end].decode('utf-8')
01604           else:
01605             val3 = str[start:end]
01606           _v67.name.append(val3)
01607         start = end
01608         end += 4
01609         (length,) = _struct_I.unpack(str[start:end])
01610         pattern = '<%sd'%length
01611         start = end
01612         end += struct.calcsize(pattern)
01613         _v67.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01614         start = end
01615         end += 4
01616         (length,) = _struct_I.unpack(str[start:end])
01617         pattern = '<%sd'%length
01618         start = end
01619         end += struct.calcsize(pattern)
01620         _v67.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01621         start = end
01622         end += 4
01623         (length,) = _struct_I.unpack(str[start:end])
01624         pattern = '<%sd'%length
01625         start = end
01626         end += struct.calcsize(pattern)
01627         _v67.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01628         _v70 = val1.grasp_posture
01629         _v71 = _v70.header
01630         start = end
01631         end += 4
01632         (_v71.seq,) = _struct_I.unpack(str[start:end])
01633         _v72 = _v71.stamp
01634         _x = _v72
01635         start = end
01636         end += 8
01637         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01638         start = end
01639         end += 4
01640         (length,) = _struct_I.unpack(str[start:end])
01641         start = end
01642         end += length
01643         if python3:
01644           _v71.frame_id = str[start:end].decode('utf-8')
01645         else:
01646           _v71.frame_id = str[start:end]
01647         start = end
01648         end += 4
01649         (length,) = _struct_I.unpack(str[start:end])
01650         _v70.name = []
01651         for i in range(0, length):
01652           start = end
01653           end += 4
01654           (length,) = _struct_I.unpack(str[start:end])
01655           start = end
01656           end += length
01657           if python3:
01658             val3 = str[start:end].decode('utf-8')
01659           else:
01660             val3 = str[start:end]
01661           _v70.name.append(val3)
01662         start = end
01663         end += 4
01664         (length,) = _struct_I.unpack(str[start:end])
01665         pattern = '<%sd'%length
01666         start = end
01667         end += struct.calcsize(pattern)
01668         _v70.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01669         start = end
01670         end += 4
01671         (length,) = _struct_I.unpack(str[start:end])
01672         pattern = '<%sd'%length
01673         start = end
01674         end += struct.calcsize(pattern)
01675         _v70.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01676         start = end
01677         end += 4
01678         (length,) = _struct_I.unpack(str[start:end])
01679         pattern = '<%sd'%length
01680         start = end
01681         end += struct.calcsize(pattern)
01682         _v70.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01683         _v73 = val1.grasp_pose
01684         _v74 = _v73.header
01685         start = end
01686         end += 4
01687         (_v74.seq,) = _struct_I.unpack(str[start:end])
01688         _v75 = _v74.stamp
01689         _x = _v75
01690         start = end
01691         end += 8
01692         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01693         start = end
01694         end += 4
01695         (length,) = _struct_I.unpack(str[start:end])
01696         start = end
01697         end += length
01698         if python3:
01699           _v74.frame_id = str[start:end].decode('utf-8')
01700         else:
01701           _v74.frame_id = str[start:end]
01702         _v76 = _v73.pose
01703         _v77 = _v76.position
01704         _x = _v77
01705         start = end
01706         end += 24
01707         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01708         _v78 = _v76.orientation
01709         _x = _v78
01710         start = end
01711         end += 32
01712         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01713         start = end
01714         end += 8
01715         (val1.grasp_quality,) = _struct_d.unpack(str[start:end])
01716         _v79 = val1.approach
01717         _v80 = _v79.direction
01718         _v81 = _v80.header
01719         start = end
01720         end += 4
01721         (_v81.seq,) = _struct_I.unpack(str[start:end])
01722         _v82 = _v81.stamp
01723         _x = _v82
01724         start = end
01725         end += 8
01726         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01727         start = end
01728         end += 4
01729         (length,) = _struct_I.unpack(str[start:end])
01730         start = end
01731         end += length
01732         if python3:
01733           _v81.frame_id = str[start:end].decode('utf-8')
01734         else:
01735           _v81.frame_id = str[start:end]
01736         _v83 = _v80.vector
01737         _x = _v83
01738         start = end
01739         end += 24
01740         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01741         _x = _v79
01742         start = end
01743         end += 8
01744         (_x.desired_distance, _x.min_distance,) = _struct_2f.unpack(str[start:end])
01745         _v84 = val1.retreat
01746         _v85 = _v84.direction
01747         _v86 = _v85.header
01748         start = end
01749         end += 4
01750         (_v86.seq,) = _struct_I.unpack(str[start:end])
01751         _v87 = _v86.stamp
01752         _x = _v87
01753         start = end
01754         end += 8
01755         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01756         start = end
01757         end += 4
01758         (length,) = _struct_I.unpack(str[start:end])
01759         start = end
01760         end += length
01761         if python3:
01762           _v86.frame_id = str[start:end].decode('utf-8')
01763         else:
01764           _v86.frame_id = str[start:end]
01765         _v88 = _v85.vector
01766         _x = _v88
01767         start = end
01768         end += 24
01769         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01770         _x = _v84
01771         start = end
01772         end += 8
01773         (_x.desired_distance, _x.min_distance,) = _struct_2f.unpack(str[start:end])
01774         start = end
01775         end += 4
01776         (val1.max_contact_force,) = _struct_f.unpack(str[start:end])
01777         start = end
01778         end += 4
01779         (length,) = _struct_I.unpack(str[start:end])
01780         val1.allowed_touch_objects = []
01781         for i in range(0, length):
01782           start = end
01783           end += 4
01784           (length,) = _struct_I.unpack(str[start:end])
01785           start = end
01786           end += length
01787           if python3:
01788             val2 = str[start:end].decode('utf-8')
01789           else:
01790             val2 = str[start:end]
01791           val1.allowed_touch_objects.append(val2)
01792         self.result.attempted_grasps.append(val1)
01793       start = end
01794       end += 4
01795       (length,) = _struct_I.unpack(str[start:end])
01796       self.result.attempted_grasp_results = []
01797       for i in range(0, length):
01798         val1 = object_manipulation_msgs.msg.GraspResult()
01799         _x = val1
01800         start = end
01801         end += 5
01802         (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
01803         val1.continuation_possible = bool(val1.continuation_possible)
01804         self.result.attempted_grasp_results.append(val1)
01805       return self
01806     except struct.error as e:
01807       raise genpy.DeserializationError(e) #most likely buffer underfill
01808 
01809 _struct_I = genpy.struct_I
01810 _struct_B = struct.Struct("<B")
01811 _struct_d = struct.Struct("<d")
01812 _struct_f = struct.Struct("<f")
01813 _struct_i = struct.Struct("<i")
01814 _struct_2f = struct.Struct("<2f")
01815 _struct_3d3f = struct.Struct("<3d3f")
01816 _struct_8d3I = struct.Struct("<8d3I")
01817 _struct_3I = struct.Struct("<3I")
01818 _struct_3d2f3I = struct.Struct("<3d2f3I")
01819 _struct_4d = struct.Struct("<4d")
01820 _struct_iB = struct.Struct("<iB")
01821 _struct_2I = struct.Struct("<2I")
01822 _struct_3d = struct.Struct("<3d")


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 02:58:11