_PlaceActionGoal.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/PlaceActionGoal.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 arm_navigation_msgs.msg
00008 import object_manipulation_msgs.msg
00009 import actionlib_msgs.msg
00010 import manipulation_msgs.msg
00011 import geometry_msgs.msg
00012 import sensor_msgs.msg
00013 import genpy
00014 import std_msgs.msg
00015 
00016 class PlaceActionGoal(genpy.Message):
00017   _md5sum = "97bc25a5d3afd0f6f096031e02e52edb"
00018   _type = "object_manipulation_msgs/PlaceActionGoal"
00019   _has_header = True #flag to mark the presence of a Header object
00020   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00021 
00022 Header header
00023 actionlib_msgs/GoalID goal_id
00024 PlaceGoal goal
00025 
00026 ================================================================================
00027 MSG: std_msgs/Header
00028 # Standard metadata for higher-level stamped data types.
00029 # This is generally used to communicate timestamped data 
00030 # in a particular coordinate frame.
00031 # 
00032 # sequence ID: consecutively increasing ID 
00033 uint32 seq
00034 #Two-integer timestamp that is expressed as:
00035 # * stamp.secs: seconds (stamp_secs) since epoch
00036 # * stamp.nsecs: nanoseconds since stamp_secs
00037 # time-handling sugar is provided by the client library
00038 time stamp
00039 #Frame this data is associated with
00040 # 0: no frame
00041 # 1: global frame
00042 string frame_id
00043 
00044 ================================================================================
00045 MSG: actionlib_msgs/GoalID
00046 # The stamp should store the time at which this goal was requested.
00047 # It is used by an action server when it tries to preempt all
00048 # goals that were requested before a certain time
00049 time stamp
00050 
00051 # The id provides a way to associate feedback and
00052 # result message with specific goal requests. The id
00053 # specified must be unique.
00054 string id
00055 
00056 
00057 ================================================================================
00058 MSG: object_manipulation_msgs/PlaceGoal
00059 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00060 # An action for placing an object
00061 
00062 # which arm to be used for grasping
00063 string arm_name
00064 
00065 # a list of possible locations for the gripper when placing
00066 # note that these refer to where the *gripper* should go when the object is placed
00067 # it is the job of the caller to make sure that these are set to that the *object*
00068 # ends up in a desired location
00069 geometry_msgs/PoseStamped[] place_locations
00070 
00071 # the grasp that has been executed on this object
00072 # (contains the grasp_pose referred to above)
00073 manipulation_msgs/Grasp grasp
00074 
00075 # how far the retreat should ideally be away from the place location
00076 float32 desired_retreat_distance
00077 
00078 # the min distance between the retreat and the place location that must actually be feasible 
00079 # for the place not to be rejected
00080 float32 min_retreat_distance
00081 
00082 # how the place location should be approached
00083 # the frame_id that this lift is specified in MUST be either the robot_frame 
00084 # or the gripper_frame specified in your hand description file
00085 GripperTranslation approach
00086 
00087 # the name that the target object has in the collision map
00088 # can be left empty if no name is available
00089 string collision_object_name
00090 
00091 # the name that the support surface (e.g. table) has in the collision map
00092 # can be left empty if no name is available
00093 string collision_support_surface_name
00094 
00095 # whether collisions between the gripper and the support surface should be acceptable
00096 # during move from pre-place to place and during retreat. Collisions when moving to the
00097 # pre-place location are still not allowed even if this is set to true.
00098 bool allow_gripper_support_collision
00099 
00100 # whether reactive placing based on tactile sensors should be used
00101 bool use_reactive_place
00102 
00103 # how much the object should be padded by when deciding if the grasp
00104 # location is freasible or not
00105 float64 place_padding
00106 
00107 # set this to true if you only want to query the manipulation pipeline as to what 
00108 # place locations it thinks are feasible, without actually executing them. If this is set to 
00109 # true, the atempted_location_results field of the result will be populated, but no arm 
00110 # movement will be attempted
00111 bool only_perform_feasibility_test
00112 
00113 # OPTIONAL (These will not have to be filled out most of the time)
00114 # constraints to be imposed on every point in the motion of the arm
00115 arm_navigation_msgs/Constraints path_constraints
00116 
00117 # OPTIONAL (These will not have to be filled out most of the time)
00118 # additional collision operations to be used for every arm movement performed
00119 # during placing. Note that these will be added on top of (and thus overide) other 
00120 # collision operations that the grasping pipeline deems necessary. Should be used
00121 # with care and only if special behaviors are desired.
00122 arm_navigation_msgs/OrderedCollisionOperations additional_collision_operations
00123 
00124 # OPTIONAL (These will not have to be filled out most of the time)
00125 # additional link paddings to be used for every arm movement performed
00126 # during placing. Note that these will be added on top of (and thus overide) other 
00127 # link paddings that the grasping pipeline deems necessary. Should be used
00128 # with care and only if special behaviors are desired.
00129 arm_navigation_msgs/LinkPadding[] additional_link_padding
00130 
00131 
00132 ================================================================================
00133 MSG: geometry_msgs/PoseStamped
00134 # A Pose with reference coordinate frame and timestamp
00135 Header header
00136 Pose pose
00137 
00138 ================================================================================
00139 MSG: geometry_msgs/Pose
00140 # A representation of pose in free space, composed of postion and orientation. 
00141 Point position
00142 Quaternion orientation
00143 
00144 ================================================================================
00145 MSG: geometry_msgs/Point
00146 # This contains the position of a point in free space
00147 float64 x
00148 float64 y
00149 float64 z
00150 
00151 ================================================================================
00152 MSG: geometry_msgs/Quaternion
00153 # This represents an orientation in free space in quaternion form.
00154 
00155 float64 x
00156 float64 y
00157 float64 z
00158 float64 w
00159 
00160 ================================================================================
00161 MSG: manipulation_msgs/Grasp
00162 # A name for this grasp
00163 string id
00164 
00165 # The internal posture of the hand for the pre-grasp
00166 # only positions are used
00167 sensor_msgs/JointState pre_grasp_posture
00168 
00169 # The internal posture of the hand for the grasp
00170 # positions and efforts are used
00171 sensor_msgs/JointState grasp_posture
00172 
00173 # The position of the end-effector for the grasp relative to a reference frame 
00174 # (that is always specified elsewhere, not in this message)
00175 geometry_msgs/PoseStamped grasp_pose
00176 
00177 # The estimated probability of success for this grasp, or some other
00178 # measure of how "good" it is.
00179 float64 grasp_quality
00180 
00181 # The approach motion
00182 GripperTranslation approach
00183 
00184 # The retreat motion
00185 GripperTranslation retreat
00186 
00187 # the maximum contact force to use while grasping (<=0 to disable)
00188 float32 max_contact_force
00189 
00190 # an optional list of obstacles that we have semantic information about
00191 # and that can be touched/pushed/moved in the course of grasping
00192 string[] allowed_touch_objects
00193 
00194 ================================================================================
00195 MSG: sensor_msgs/JointState
00196 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00197 #
00198 # The state of each joint (revolute or prismatic) is defined by:
00199 #  * the position of the joint (rad or m),
00200 #  * the velocity of the joint (rad/s or m/s) and 
00201 #  * the effort that is applied in the joint (Nm or N).
00202 #
00203 # Each joint is uniquely identified by its name
00204 # The header specifies the time at which the joint states were recorded. All the joint states
00205 # in one message have to be recorded at the same time.
00206 #
00207 # This message consists of a multiple arrays, one for each part of the joint state. 
00208 # The goal is to make each of the fields optional. When e.g. your joints have no
00209 # effort associated with them, you can leave the effort array empty. 
00210 #
00211 # All arrays in this message should have the same size, or be empty.
00212 # This is the only way to uniquely associate the joint name with the correct
00213 # states.
00214 
00215 
00216 Header header
00217 
00218 string[] name
00219 float64[] position
00220 float64[] velocity
00221 float64[] effort
00222 
00223 ================================================================================
00224 MSG: manipulation_msgs/GripperTranslation
00225 # defines a translation for the gripper, used in pickup or place tasks
00226 # for example for lifting an object off a table or approaching the table for placing
00227 
00228 # the direction of the translation
00229 geometry_msgs/Vector3Stamped direction
00230 
00231 # the desired translation distance
00232 float32 desired_distance
00233 
00234 # the min distance that must be considered feasible before the
00235 # grasp is even attempted
00236 float32 min_distance
00237 
00238 ================================================================================
00239 MSG: geometry_msgs/Vector3Stamped
00240 # This represents a Vector3 with reference coordinate frame and timestamp
00241 Header header
00242 Vector3 vector
00243 
00244 ================================================================================
00245 MSG: geometry_msgs/Vector3
00246 # This represents a vector in free space. 
00247 
00248 float64 x
00249 float64 y
00250 float64 z
00251 ================================================================================
00252 MSG: object_manipulation_msgs/GripperTranslation
00253 # defines a translation for the gripper, used in pickup or place tasks
00254 # for example for lifting an object off a table or approaching the table for placing
00255 
00256 # the direction of the translation
00257 geometry_msgs/Vector3Stamped direction
00258 
00259 # the desired translation distance
00260 float32 desired_distance
00261 
00262 # the min distance that must be considered feasible before the
00263 # grasp is even attempted
00264 float32 min_distance
00265 ================================================================================
00266 MSG: arm_navigation_msgs/Constraints
00267 # This message contains a list of motion planning constraints.
00268 
00269 arm_navigation_msgs/JointConstraint[] joint_constraints
00270 arm_navigation_msgs/PositionConstraint[] position_constraints
00271 arm_navigation_msgs/OrientationConstraint[] orientation_constraints
00272 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints
00273 
00274 ================================================================================
00275 MSG: arm_navigation_msgs/JointConstraint
00276 # Constrain the position of a joint to be within a certain bound
00277 string joint_name
00278 
00279 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00280 float64 position
00281 float64 tolerance_above
00282 float64 tolerance_below
00283 
00284 # A weighting factor for this constraint
00285 float64 weight
00286 ================================================================================
00287 MSG: arm_navigation_msgs/PositionConstraint
00288 # This message contains the definition of a position constraint.
00289 Header header
00290 
00291 # The robot link this constraint refers to
00292 string link_name
00293 
00294 # The offset (in the link frame) for the target point on the link we are planning for
00295 geometry_msgs/Point target_point_offset
00296 
00297 # The nominal/target position for the point we are planning for
00298 geometry_msgs/Point position
00299 
00300 # The shape of the bounded region that constrains the position of the end-effector
00301 # This region is always centered at the position defined above
00302 arm_navigation_msgs/Shape constraint_region_shape
00303 
00304 # The orientation of the bounded region that constrains the position of the end-effector. 
00305 # This allows the specification of non-axis aligned constraints
00306 geometry_msgs/Quaternion constraint_region_orientation
00307 
00308 # Constraint weighting factor - a weight for this constraint
00309 float64 weight
00310 
00311 ================================================================================
00312 MSG: arm_navigation_msgs/Shape
00313 byte SPHERE=0
00314 byte BOX=1
00315 byte CYLINDER=2
00316 byte MESH=3
00317 
00318 byte type
00319 
00320 
00321 #### define sphere, box, cylinder ####
00322 # the origin of each shape is considered at the shape's center
00323 
00324 # for sphere
00325 # radius := dimensions[0]
00326 
00327 # for cylinder
00328 # radius := dimensions[0]
00329 # length := dimensions[1]
00330 # the length is along the Z axis
00331 
00332 # for box
00333 # size_x := dimensions[0]
00334 # size_y := dimensions[1]
00335 # size_z := dimensions[2]
00336 float64[] dimensions
00337 
00338 
00339 #### define mesh ####
00340 
00341 # list of triangles; triangle k is defined by tre vertices located
00342 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00343 int32[] triangles
00344 geometry_msgs/Point[] vertices
00345 
00346 ================================================================================
00347 MSG: arm_navigation_msgs/OrientationConstraint
00348 # This message contains the definition of an orientation constraint.
00349 Header header
00350 
00351 # The robot link this constraint refers to
00352 string link_name
00353 
00354 # The type of the constraint
00355 int32 type
00356 int32 LINK_FRAME=0
00357 int32 HEADER_FRAME=1
00358 
00359 # The desired orientation of the robot link specified as a quaternion
00360 geometry_msgs/Quaternion orientation
00361 
00362 # optional RPY error tolerances specified if 
00363 float64 absolute_roll_tolerance
00364 float64 absolute_pitch_tolerance
00365 float64 absolute_yaw_tolerance
00366 
00367 # Constraint weighting factor - a weight for this constraint
00368 float64 weight
00369 
00370 ================================================================================
00371 MSG: arm_navigation_msgs/VisibilityConstraint
00372 # This message contains the definition of a visibility constraint.
00373 Header header
00374 
00375 # The point stamped target that needs to be kept within view of the sensor
00376 geometry_msgs/PointStamped target
00377 
00378 # The local pose of the frame in which visibility is to be maintained
00379 # The frame id should represent the robot link to which the sensor is attached
00380 # The visual axis of the sensor is assumed to be along the X axis of this frame
00381 geometry_msgs/PoseStamped sensor_pose
00382 
00383 # The deviation (in radians) that will be tolerated
00384 # Constraint error will be measured as the solid angle between the 
00385 # X axis of the frame defined above and the vector between the origin 
00386 # of the frame defined above and the target location
00387 float64 absolute_tolerance
00388 
00389 
00390 ================================================================================
00391 MSG: geometry_msgs/PointStamped
00392 # This represents a Point with reference coordinate frame and timestamp
00393 Header header
00394 Point point
00395 
00396 ================================================================================
00397 MSG: arm_navigation_msgs/OrderedCollisionOperations
00398 # A set of collision operations that will be performed in the order they are specified
00399 CollisionOperation[] collision_operations
00400 ================================================================================
00401 MSG: arm_navigation_msgs/CollisionOperation
00402 # A definition of a collision operation
00403 # E.g. ("gripper",COLLISION_SET_ALL,ENABLE) will enable collisions 
00404 # between the gripper and all objects in the collision space
00405 
00406 string object1
00407 string object2
00408 string COLLISION_SET_ALL="all"
00409 string COLLISION_SET_OBJECTS="objects"
00410 string COLLISION_SET_ATTACHED_OBJECTS="attached"
00411 
00412 # The penetration distance to which collisions are allowed. This is 0.0 by default.
00413 float64 penetration_distance
00414 
00415 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above
00416 int32 operation
00417 int32 DISABLE=0
00418 int32 ENABLE=1
00419 
00420 ================================================================================
00421 MSG: arm_navigation_msgs/LinkPadding
00422 #name for the link
00423 string link_name
00424 
00425 # padding to apply to the link
00426 float64 padding
00427 
00428 """
00429   __slots__ = ['header','goal_id','goal']
00430   _slot_types = ['std_msgs/Header','actionlib_msgs/GoalID','object_manipulation_msgs/PlaceGoal']
00431 
00432   def __init__(self, *args, **kwds):
00433     """
00434     Constructor. Any message fields that are implicitly/explicitly
00435     set to None will be assigned a default value. The recommend
00436     use is keyword arguments as this is more robust to future message
00437     changes.  You cannot mix in-order arguments and keyword arguments.
00438 
00439     The available fields are:
00440        header,goal_id,goal
00441 
00442     :param args: complete set of field values, in .msg order
00443     :param kwds: use keyword arguments corresponding to message field names
00444     to set specific fields.
00445     """
00446     if args or kwds:
00447       super(PlaceActionGoal, self).__init__(*args, **kwds)
00448       #message fields cannot be None, assign default values for those that are
00449       if self.header is None:
00450         self.header = std_msgs.msg.Header()
00451       if self.goal_id is None:
00452         self.goal_id = actionlib_msgs.msg.GoalID()
00453       if self.goal is None:
00454         self.goal = object_manipulation_msgs.msg.PlaceGoal()
00455     else:
00456       self.header = std_msgs.msg.Header()
00457       self.goal_id = actionlib_msgs.msg.GoalID()
00458       self.goal = object_manipulation_msgs.msg.PlaceGoal()
00459 
00460   def _get_types(self):
00461     """
00462     internal API method
00463     """
00464     return self._slot_types
00465 
00466   def serialize(self, buff):
00467     """
00468     serialize message into buffer
00469     :param buff: buffer, ``StringIO``
00470     """
00471     try:
00472       _x = self
00473       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00474       _x = self.header.frame_id
00475       length = len(_x)
00476       if python3 or type(_x) == unicode:
00477         _x = _x.encode('utf-8')
00478         length = len(_x)
00479       buff.write(struct.pack('<I%ss'%length, length, _x))
00480       _x = self
00481       buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00482       _x = self.goal_id.id
00483       length = len(_x)
00484       if python3 or type(_x) == unicode:
00485         _x = _x.encode('utf-8')
00486         length = len(_x)
00487       buff.write(struct.pack('<I%ss'%length, length, _x))
00488       _x = self.goal.arm_name
00489       length = len(_x)
00490       if python3 or type(_x) == unicode:
00491         _x = _x.encode('utf-8')
00492         length = len(_x)
00493       buff.write(struct.pack('<I%ss'%length, length, _x))
00494       length = len(self.goal.place_locations)
00495       buff.write(_struct_I.pack(length))
00496       for val1 in self.goal.place_locations:
00497         _v1 = val1.header
00498         buff.write(_struct_I.pack(_v1.seq))
00499         _v2 = _v1.stamp
00500         _x = _v2
00501         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00502         _x = _v1.frame_id
00503         length = len(_x)
00504         if python3 or type(_x) == unicode:
00505           _x = _x.encode('utf-8')
00506           length = len(_x)
00507         buff.write(struct.pack('<I%ss'%length, length, _x))
00508         _v3 = val1.pose
00509         _v4 = _v3.position
00510         _x = _v4
00511         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00512         _v5 = _v3.orientation
00513         _x = _v5
00514         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00515       _x = self.goal.grasp.id
00516       length = len(_x)
00517       if python3 or type(_x) == unicode:
00518         _x = _x.encode('utf-8')
00519         length = len(_x)
00520       buff.write(struct.pack('<I%ss'%length, length, _x))
00521       _x = self
00522       buff.write(_struct_3I.pack(_x.goal.grasp.pre_grasp_posture.header.seq, _x.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.goal.grasp.pre_grasp_posture.header.stamp.nsecs))
00523       _x = self.goal.grasp.pre_grasp_posture.header.frame_id
00524       length = len(_x)
00525       if python3 or type(_x) == unicode:
00526         _x = _x.encode('utf-8')
00527         length = len(_x)
00528       buff.write(struct.pack('<I%ss'%length, length, _x))
00529       length = len(self.goal.grasp.pre_grasp_posture.name)
00530       buff.write(_struct_I.pack(length))
00531       for val1 in self.goal.grasp.pre_grasp_posture.name:
00532         length = len(val1)
00533         if python3 or type(val1) == unicode:
00534           val1 = val1.encode('utf-8')
00535           length = len(val1)
00536         buff.write(struct.pack('<I%ss'%length, length, val1))
00537       length = len(self.goal.grasp.pre_grasp_posture.position)
00538       buff.write(_struct_I.pack(length))
00539       pattern = '<%sd'%length
00540       buff.write(struct.pack(pattern, *self.goal.grasp.pre_grasp_posture.position))
00541       length = len(self.goal.grasp.pre_grasp_posture.velocity)
00542       buff.write(_struct_I.pack(length))
00543       pattern = '<%sd'%length
00544       buff.write(struct.pack(pattern, *self.goal.grasp.pre_grasp_posture.velocity))
00545       length = len(self.goal.grasp.pre_grasp_posture.effort)
00546       buff.write(_struct_I.pack(length))
00547       pattern = '<%sd'%length
00548       buff.write(struct.pack(pattern, *self.goal.grasp.pre_grasp_posture.effort))
00549       _x = self
00550       buff.write(_struct_3I.pack(_x.goal.grasp.grasp_posture.header.seq, _x.goal.grasp.grasp_posture.header.stamp.secs, _x.goal.grasp.grasp_posture.header.stamp.nsecs))
00551       _x = self.goal.grasp.grasp_posture.header.frame_id
00552       length = len(_x)
00553       if python3 or type(_x) == unicode:
00554         _x = _x.encode('utf-8')
00555         length = len(_x)
00556       buff.write(struct.pack('<I%ss'%length, length, _x))
00557       length = len(self.goal.grasp.grasp_posture.name)
00558       buff.write(_struct_I.pack(length))
00559       for val1 in self.goal.grasp.grasp_posture.name:
00560         length = len(val1)
00561         if python3 or type(val1) == unicode:
00562           val1 = val1.encode('utf-8')
00563           length = len(val1)
00564         buff.write(struct.pack('<I%ss'%length, length, val1))
00565       length = len(self.goal.grasp.grasp_posture.position)
00566       buff.write(_struct_I.pack(length))
00567       pattern = '<%sd'%length
00568       buff.write(struct.pack(pattern, *self.goal.grasp.grasp_posture.position))
00569       length = len(self.goal.grasp.grasp_posture.velocity)
00570       buff.write(_struct_I.pack(length))
00571       pattern = '<%sd'%length
00572       buff.write(struct.pack(pattern, *self.goal.grasp.grasp_posture.velocity))
00573       length = len(self.goal.grasp.grasp_posture.effort)
00574       buff.write(_struct_I.pack(length))
00575       pattern = '<%sd'%length
00576       buff.write(struct.pack(pattern, *self.goal.grasp.grasp_posture.effort))
00577       _x = self
00578       buff.write(_struct_3I.pack(_x.goal.grasp.grasp_pose.header.seq, _x.goal.grasp.grasp_pose.header.stamp.secs, _x.goal.grasp.grasp_pose.header.stamp.nsecs))
00579       _x = self.goal.grasp.grasp_pose.header.frame_id
00580       length = len(_x)
00581       if python3 or type(_x) == unicode:
00582         _x = _x.encode('utf-8')
00583         length = len(_x)
00584       buff.write(struct.pack('<I%ss'%length, length, _x))
00585       _x = self
00586       buff.write(_struct_8d3I.pack(_x.goal.grasp.grasp_pose.pose.position.x, _x.goal.grasp.grasp_pose.pose.position.y, _x.goal.grasp.grasp_pose.pose.position.z, _x.goal.grasp.grasp_pose.pose.orientation.x, _x.goal.grasp.grasp_pose.pose.orientation.y, _x.goal.grasp.grasp_pose.pose.orientation.z, _x.goal.grasp.grasp_pose.pose.orientation.w, _x.goal.grasp.grasp_quality, _x.goal.grasp.approach.direction.header.seq, _x.goal.grasp.approach.direction.header.stamp.secs, _x.goal.grasp.approach.direction.header.stamp.nsecs))
00587       _x = self.goal.grasp.approach.direction.header.frame_id
00588       length = len(_x)
00589       if python3 or type(_x) == unicode:
00590         _x = _x.encode('utf-8')
00591         length = len(_x)
00592       buff.write(struct.pack('<I%ss'%length, length, _x))
00593       _x = self
00594       buff.write(_struct_3d2f3I.pack(_x.goal.grasp.approach.direction.vector.x, _x.goal.grasp.approach.direction.vector.y, _x.goal.grasp.approach.direction.vector.z, _x.goal.grasp.approach.desired_distance, _x.goal.grasp.approach.min_distance, _x.goal.grasp.retreat.direction.header.seq, _x.goal.grasp.retreat.direction.header.stamp.secs, _x.goal.grasp.retreat.direction.header.stamp.nsecs))
00595       _x = self.goal.grasp.retreat.direction.header.frame_id
00596       length = len(_x)
00597       if python3 or type(_x) == unicode:
00598         _x = _x.encode('utf-8')
00599         length = len(_x)
00600       buff.write(struct.pack('<I%ss'%length, length, _x))
00601       _x = self
00602       buff.write(_struct_3d3f.pack(_x.goal.grasp.retreat.direction.vector.x, _x.goal.grasp.retreat.direction.vector.y, _x.goal.grasp.retreat.direction.vector.z, _x.goal.grasp.retreat.desired_distance, _x.goal.grasp.retreat.min_distance, _x.goal.grasp.max_contact_force))
00603       length = len(self.goal.grasp.allowed_touch_objects)
00604       buff.write(_struct_I.pack(length))
00605       for val1 in self.goal.grasp.allowed_touch_objects:
00606         length = len(val1)
00607         if python3 or type(val1) == unicode:
00608           val1 = val1.encode('utf-8')
00609           length = len(val1)
00610         buff.write(struct.pack('<I%ss'%length, length, val1))
00611       _x = self
00612       buff.write(_struct_2f3I.pack(_x.goal.desired_retreat_distance, _x.goal.min_retreat_distance, _x.goal.approach.direction.header.seq, _x.goal.approach.direction.header.stamp.secs, _x.goal.approach.direction.header.stamp.nsecs))
00613       _x = self.goal.approach.direction.header.frame_id
00614       length = len(_x)
00615       if python3 or type(_x) == unicode:
00616         _x = _x.encode('utf-8')
00617         length = len(_x)
00618       buff.write(struct.pack('<I%ss'%length, length, _x))
00619       _x = self
00620       buff.write(_struct_3d2f.pack(_x.goal.approach.direction.vector.x, _x.goal.approach.direction.vector.y, _x.goal.approach.direction.vector.z, _x.goal.approach.desired_distance, _x.goal.approach.min_distance))
00621       _x = self.goal.collision_object_name
00622       length = len(_x)
00623       if python3 or type(_x) == unicode:
00624         _x = _x.encode('utf-8')
00625         length = len(_x)
00626       buff.write(struct.pack('<I%ss'%length, length, _x))
00627       _x = self.goal.collision_support_surface_name
00628       length = len(_x)
00629       if python3 or type(_x) == unicode:
00630         _x = _x.encode('utf-8')
00631         length = len(_x)
00632       buff.write(struct.pack('<I%ss'%length, length, _x))
00633       _x = self
00634       buff.write(_struct_2BdB.pack(_x.goal.allow_gripper_support_collision, _x.goal.use_reactive_place, _x.goal.place_padding, _x.goal.only_perform_feasibility_test))
00635       length = len(self.goal.path_constraints.joint_constraints)
00636       buff.write(_struct_I.pack(length))
00637       for val1 in self.goal.path_constraints.joint_constraints:
00638         _x = val1.joint_name
00639         length = len(_x)
00640         if python3 or type(_x) == unicode:
00641           _x = _x.encode('utf-8')
00642           length = len(_x)
00643         buff.write(struct.pack('<I%ss'%length, length, _x))
00644         _x = val1
00645         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00646       length = len(self.goal.path_constraints.position_constraints)
00647       buff.write(_struct_I.pack(length))
00648       for val1 in self.goal.path_constraints.position_constraints:
00649         _v6 = val1.header
00650         buff.write(_struct_I.pack(_v6.seq))
00651         _v7 = _v6.stamp
00652         _x = _v7
00653         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00654         _x = _v6.frame_id
00655         length = len(_x)
00656         if python3 or type(_x) == unicode:
00657           _x = _x.encode('utf-8')
00658           length = len(_x)
00659         buff.write(struct.pack('<I%ss'%length, length, _x))
00660         _x = val1.link_name
00661         length = len(_x)
00662         if python3 or type(_x) == unicode:
00663           _x = _x.encode('utf-8')
00664           length = len(_x)
00665         buff.write(struct.pack('<I%ss'%length, length, _x))
00666         _v8 = val1.target_point_offset
00667         _x = _v8
00668         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00669         _v9 = val1.position
00670         _x = _v9
00671         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00672         _v10 = val1.constraint_region_shape
00673         buff.write(_struct_b.pack(_v10.type))
00674         length = len(_v10.dimensions)
00675         buff.write(_struct_I.pack(length))
00676         pattern = '<%sd'%length
00677         buff.write(struct.pack(pattern, *_v10.dimensions))
00678         length = len(_v10.triangles)
00679         buff.write(_struct_I.pack(length))
00680         pattern = '<%si'%length
00681         buff.write(struct.pack(pattern, *_v10.triangles))
00682         length = len(_v10.vertices)
00683         buff.write(_struct_I.pack(length))
00684         for val3 in _v10.vertices:
00685           _x = val3
00686           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00687         _v11 = val1.constraint_region_orientation
00688         _x = _v11
00689         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00690         buff.write(_struct_d.pack(val1.weight))
00691       length = len(self.goal.path_constraints.orientation_constraints)
00692       buff.write(_struct_I.pack(length))
00693       for val1 in self.goal.path_constraints.orientation_constraints:
00694         _v12 = val1.header
00695         buff.write(_struct_I.pack(_v12.seq))
00696         _v13 = _v12.stamp
00697         _x = _v13
00698         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00699         _x = _v12.frame_id
00700         length = len(_x)
00701         if python3 or type(_x) == unicode:
00702           _x = _x.encode('utf-8')
00703           length = len(_x)
00704         buff.write(struct.pack('<I%ss'%length, length, _x))
00705         _x = val1.link_name
00706         length = len(_x)
00707         if python3 or type(_x) == unicode:
00708           _x = _x.encode('utf-8')
00709           length = len(_x)
00710         buff.write(struct.pack('<I%ss'%length, length, _x))
00711         buff.write(_struct_i.pack(val1.type))
00712         _v14 = val1.orientation
00713         _x = _v14
00714         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00715         _x = val1
00716         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00717       length = len(self.goal.path_constraints.visibility_constraints)
00718       buff.write(_struct_I.pack(length))
00719       for val1 in self.goal.path_constraints.visibility_constraints:
00720         _v15 = val1.header
00721         buff.write(_struct_I.pack(_v15.seq))
00722         _v16 = _v15.stamp
00723         _x = _v16
00724         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00725         _x = _v15.frame_id
00726         length = len(_x)
00727         if python3 or type(_x) == unicode:
00728           _x = _x.encode('utf-8')
00729           length = len(_x)
00730         buff.write(struct.pack('<I%ss'%length, length, _x))
00731         _v17 = val1.target
00732         _v18 = _v17.header
00733         buff.write(_struct_I.pack(_v18.seq))
00734         _v19 = _v18.stamp
00735         _x = _v19
00736         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00737         _x = _v18.frame_id
00738         length = len(_x)
00739         if python3 or type(_x) == unicode:
00740           _x = _x.encode('utf-8')
00741           length = len(_x)
00742         buff.write(struct.pack('<I%ss'%length, length, _x))
00743         _v20 = _v17.point
00744         _x = _v20
00745         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00746         _v21 = val1.sensor_pose
00747         _v22 = _v21.header
00748         buff.write(_struct_I.pack(_v22.seq))
00749         _v23 = _v22.stamp
00750         _x = _v23
00751         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00752         _x = _v22.frame_id
00753         length = len(_x)
00754         if python3 or type(_x) == unicode:
00755           _x = _x.encode('utf-8')
00756           length = len(_x)
00757         buff.write(struct.pack('<I%ss'%length, length, _x))
00758         _v24 = _v21.pose
00759         _v25 = _v24.position
00760         _x = _v25
00761         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00762         _v26 = _v24.orientation
00763         _x = _v26
00764         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00765         buff.write(_struct_d.pack(val1.absolute_tolerance))
00766       length = len(self.goal.additional_collision_operations.collision_operations)
00767       buff.write(_struct_I.pack(length))
00768       for val1 in self.goal.additional_collision_operations.collision_operations:
00769         _x = val1.object1
00770         length = len(_x)
00771         if python3 or type(_x) == unicode:
00772           _x = _x.encode('utf-8')
00773           length = len(_x)
00774         buff.write(struct.pack('<I%ss'%length, length, _x))
00775         _x = val1.object2
00776         length = len(_x)
00777         if python3 or type(_x) == unicode:
00778           _x = _x.encode('utf-8')
00779           length = len(_x)
00780         buff.write(struct.pack('<I%ss'%length, length, _x))
00781         _x = val1
00782         buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
00783       length = len(self.goal.additional_link_padding)
00784       buff.write(_struct_I.pack(length))
00785       for val1 in self.goal.additional_link_padding:
00786         _x = val1.link_name
00787         length = len(_x)
00788         if python3 or type(_x) == unicode:
00789           _x = _x.encode('utf-8')
00790           length = len(_x)
00791         buff.write(struct.pack('<I%ss'%length, length, _x))
00792         buff.write(_struct_d.pack(val1.padding))
00793     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00794     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00795 
00796   def deserialize(self, str):
00797     """
00798     unpack serialized message in str into this message instance
00799     :param str: byte array of serialized message, ``str``
00800     """
00801     try:
00802       if self.header is None:
00803         self.header = std_msgs.msg.Header()
00804       if self.goal_id is None:
00805         self.goal_id = actionlib_msgs.msg.GoalID()
00806       if self.goal is None:
00807         self.goal = object_manipulation_msgs.msg.PlaceGoal()
00808       end = 0
00809       _x = self
00810       start = end
00811       end += 12
00812       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00813       start = end
00814       end += 4
00815       (length,) = _struct_I.unpack(str[start:end])
00816       start = end
00817       end += length
00818       if python3:
00819         self.header.frame_id = str[start:end].decode('utf-8')
00820       else:
00821         self.header.frame_id = str[start:end]
00822       _x = self
00823       start = end
00824       end += 8
00825       (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00826       start = end
00827       end += 4
00828       (length,) = _struct_I.unpack(str[start:end])
00829       start = end
00830       end += length
00831       if python3:
00832         self.goal_id.id = str[start:end].decode('utf-8')
00833       else:
00834         self.goal_id.id = str[start:end]
00835       start = end
00836       end += 4
00837       (length,) = _struct_I.unpack(str[start:end])
00838       start = end
00839       end += length
00840       if python3:
00841         self.goal.arm_name = str[start:end].decode('utf-8')
00842       else:
00843         self.goal.arm_name = str[start:end]
00844       start = end
00845       end += 4
00846       (length,) = _struct_I.unpack(str[start:end])
00847       self.goal.place_locations = []
00848       for i in range(0, length):
00849         val1 = geometry_msgs.msg.PoseStamped()
00850         _v27 = val1.header
00851         start = end
00852         end += 4
00853         (_v27.seq,) = _struct_I.unpack(str[start:end])
00854         _v28 = _v27.stamp
00855         _x = _v28
00856         start = end
00857         end += 8
00858         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00859         start = end
00860         end += 4
00861         (length,) = _struct_I.unpack(str[start:end])
00862         start = end
00863         end += length
00864         if python3:
00865           _v27.frame_id = str[start:end].decode('utf-8')
00866         else:
00867           _v27.frame_id = str[start:end]
00868         _v29 = val1.pose
00869         _v30 = _v29.position
00870         _x = _v30
00871         start = end
00872         end += 24
00873         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00874         _v31 = _v29.orientation
00875         _x = _v31
00876         start = end
00877         end += 32
00878         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00879         self.goal.place_locations.append(val1)
00880       start = end
00881       end += 4
00882       (length,) = _struct_I.unpack(str[start:end])
00883       start = end
00884       end += length
00885       if python3:
00886         self.goal.grasp.id = str[start:end].decode('utf-8')
00887       else:
00888         self.goal.grasp.id = str[start:end]
00889       _x = self
00890       start = end
00891       end += 12
00892       (_x.goal.grasp.pre_grasp_posture.header.seq, _x.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.goal.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.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         self.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
00900       else:
00901         self.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end]
00902       start = end
00903       end += 4
00904       (length,) = _struct_I.unpack(str[start:end])
00905       self.goal.grasp.pre_grasp_posture.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           val1 = str[start:end].decode('utf-8')
00914         else:
00915           val1 = str[start:end]
00916         self.goal.grasp.pre_grasp_posture.name.append(val1)
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       self.goal.grasp.pre_grasp_posture.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       self.goal.grasp.pre_grasp_posture.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       self.goal.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end])
00938       _x = self
00939       start = end
00940       end += 12
00941       (_x.goal.grasp.grasp_posture.header.seq, _x.goal.grasp.grasp_posture.header.stamp.secs, _x.goal.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00942       start = end
00943       end += 4
00944       (length,) = _struct_I.unpack(str[start:end])
00945       start = end
00946       end += length
00947       if python3:
00948         self.goal.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
00949       else:
00950         self.goal.grasp.grasp_posture.header.frame_id = str[start:end]
00951       start = end
00952       end += 4
00953       (length,) = _struct_I.unpack(str[start:end])
00954       self.goal.grasp.grasp_posture.name = []
00955       for i in range(0, length):
00956         start = end
00957         end += 4
00958         (length,) = _struct_I.unpack(str[start:end])
00959         start = end
00960         end += length
00961         if python3:
00962           val1 = str[start:end].decode('utf-8')
00963         else:
00964           val1 = str[start:end]
00965         self.goal.grasp.grasp_posture.name.append(val1)
00966       start = end
00967       end += 4
00968       (length,) = _struct_I.unpack(str[start:end])
00969       pattern = '<%sd'%length
00970       start = end
00971       end += struct.calcsize(pattern)
00972       self.goal.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end])
00973       start = end
00974       end += 4
00975       (length,) = _struct_I.unpack(str[start:end])
00976       pattern = '<%sd'%length
00977       start = end
00978       end += struct.calcsize(pattern)
00979       self.goal.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00980       start = end
00981       end += 4
00982       (length,) = _struct_I.unpack(str[start:end])
00983       pattern = '<%sd'%length
00984       start = end
00985       end += struct.calcsize(pattern)
00986       self.goal.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end])
00987       _x = self
00988       start = end
00989       end += 12
00990       (_x.goal.grasp.grasp_pose.header.seq, _x.goal.grasp.grasp_pose.header.stamp.secs, _x.goal.grasp.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00991       start = end
00992       end += 4
00993       (length,) = _struct_I.unpack(str[start:end])
00994       start = end
00995       end += length
00996       if python3:
00997         self.goal.grasp.grasp_pose.header.frame_id = str[start:end].decode('utf-8')
00998       else:
00999         self.goal.grasp.grasp_pose.header.frame_id = str[start:end]
01000       _x = self
01001       start = end
01002       end += 76
01003       (_x.goal.grasp.grasp_pose.pose.position.x, _x.goal.grasp.grasp_pose.pose.position.y, _x.goal.grasp.grasp_pose.pose.position.z, _x.goal.grasp.grasp_pose.pose.orientation.x, _x.goal.grasp.grasp_pose.pose.orientation.y, _x.goal.grasp.grasp_pose.pose.orientation.z, _x.goal.grasp.grasp_pose.pose.orientation.w, _x.goal.grasp.grasp_quality, _x.goal.grasp.approach.direction.header.seq, _x.goal.grasp.approach.direction.header.stamp.secs, _x.goal.grasp.approach.direction.header.stamp.nsecs,) = _struct_8d3I.unpack(str[start:end])
01004       start = end
01005       end += 4
01006       (length,) = _struct_I.unpack(str[start:end])
01007       start = end
01008       end += length
01009       if python3:
01010         self.goal.grasp.approach.direction.header.frame_id = str[start:end].decode('utf-8')
01011       else:
01012         self.goal.grasp.approach.direction.header.frame_id = str[start:end]
01013       _x = self
01014       start = end
01015       end += 44
01016       (_x.goal.grasp.approach.direction.vector.x, _x.goal.grasp.approach.direction.vector.y, _x.goal.grasp.approach.direction.vector.z, _x.goal.grasp.approach.desired_distance, _x.goal.grasp.approach.min_distance, _x.goal.grasp.retreat.direction.header.seq, _x.goal.grasp.retreat.direction.header.stamp.secs, _x.goal.grasp.retreat.direction.header.stamp.nsecs,) = _struct_3d2f3I.unpack(str[start:end])
01017       start = end
01018       end += 4
01019       (length,) = _struct_I.unpack(str[start:end])
01020       start = end
01021       end += length
01022       if python3:
01023         self.goal.grasp.retreat.direction.header.frame_id = str[start:end].decode('utf-8')
01024       else:
01025         self.goal.grasp.retreat.direction.header.frame_id = str[start:end]
01026       _x = self
01027       start = end
01028       end += 36
01029       (_x.goal.grasp.retreat.direction.vector.x, _x.goal.grasp.retreat.direction.vector.y, _x.goal.grasp.retreat.direction.vector.z, _x.goal.grasp.retreat.desired_distance, _x.goal.grasp.retreat.min_distance, _x.goal.grasp.max_contact_force,) = _struct_3d3f.unpack(str[start:end])
01030       start = end
01031       end += 4
01032       (length,) = _struct_I.unpack(str[start:end])
01033       self.goal.grasp.allowed_touch_objects = []
01034       for i in range(0, length):
01035         start = end
01036         end += 4
01037         (length,) = _struct_I.unpack(str[start:end])
01038         start = end
01039         end += length
01040         if python3:
01041           val1 = str[start:end].decode('utf-8')
01042         else:
01043           val1 = str[start:end]
01044         self.goal.grasp.allowed_touch_objects.append(val1)
01045       _x = self
01046       start = end
01047       end += 20
01048       (_x.goal.desired_retreat_distance, _x.goal.min_retreat_distance, _x.goal.approach.direction.header.seq, _x.goal.approach.direction.header.stamp.secs, _x.goal.approach.direction.header.stamp.nsecs,) = _struct_2f3I.unpack(str[start:end])
01049       start = end
01050       end += 4
01051       (length,) = _struct_I.unpack(str[start:end])
01052       start = end
01053       end += length
01054       if python3:
01055         self.goal.approach.direction.header.frame_id = str[start:end].decode('utf-8')
01056       else:
01057         self.goal.approach.direction.header.frame_id = str[start:end]
01058       _x = self
01059       start = end
01060       end += 32
01061       (_x.goal.approach.direction.vector.x, _x.goal.approach.direction.vector.y, _x.goal.approach.direction.vector.z, _x.goal.approach.desired_distance, _x.goal.approach.min_distance,) = _struct_3d2f.unpack(str[start:end])
01062       start = end
01063       end += 4
01064       (length,) = _struct_I.unpack(str[start:end])
01065       start = end
01066       end += length
01067       if python3:
01068         self.goal.collision_object_name = str[start:end].decode('utf-8')
01069       else:
01070         self.goal.collision_object_name = str[start:end]
01071       start = end
01072       end += 4
01073       (length,) = _struct_I.unpack(str[start:end])
01074       start = end
01075       end += length
01076       if python3:
01077         self.goal.collision_support_surface_name = str[start:end].decode('utf-8')
01078       else:
01079         self.goal.collision_support_surface_name = str[start:end]
01080       _x = self
01081       start = end
01082       end += 11
01083       (_x.goal.allow_gripper_support_collision, _x.goal.use_reactive_place, _x.goal.place_padding, _x.goal.only_perform_feasibility_test,) = _struct_2BdB.unpack(str[start:end])
01084       self.goal.allow_gripper_support_collision = bool(self.goal.allow_gripper_support_collision)
01085       self.goal.use_reactive_place = bool(self.goal.use_reactive_place)
01086       self.goal.only_perform_feasibility_test = bool(self.goal.only_perform_feasibility_test)
01087       start = end
01088       end += 4
01089       (length,) = _struct_I.unpack(str[start:end])
01090       self.goal.path_constraints.joint_constraints = []
01091       for i in range(0, length):
01092         val1 = arm_navigation_msgs.msg.JointConstraint()
01093         start = end
01094         end += 4
01095         (length,) = _struct_I.unpack(str[start:end])
01096         start = end
01097         end += length
01098         if python3:
01099           val1.joint_name = str[start:end].decode('utf-8')
01100         else:
01101           val1.joint_name = str[start:end]
01102         _x = val1
01103         start = end
01104         end += 32
01105         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01106         self.goal.path_constraints.joint_constraints.append(val1)
01107       start = end
01108       end += 4
01109       (length,) = _struct_I.unpack(str[start:end])
01110       self.goal.path_constraints.position_constraints = []
01111       for i in range(0, length):
01112         val1 = arm_navigation_msgs.msg.PositionConstraint()
01113         _v32 = val1.header
01114         start = end
01115         end += 4
01116         (_v32.seq,) = _struct_I.unpack(str[start:end])
01117         _v33 = _v32.stamp
01118         _x = _v33
01119         start = end
01120         end += 8
01121         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01122         start = end
01123         end += 4
01124         (length,) = _struct_I.unpack(str[start:end])
01125         start = end
01126         end += length
01127         if python3:
01128           _v32.frame_id = str[start:end].decode('utf-8')
01129         else:
01130           _v32.frame_id = str[start:end]
01131         start = end
01132         end += 4
01133         (length,) = _struct_I.unpack(str[start:end])
01134         start = end
01135         end += length
01136         if python3:
01137           val1.link_name = str[start:end].decode('utf-8')
01138         else:
01139           val1.link_name = str[start:end]
01140         _v34 = val1.target_point_offset
01141         _x = _v34
01142         start = end
01143         end += 24
01144         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01145         _v35 = val1.position
01146         _x = _v35
01147         start = end
01148         end += 24
01149         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01150         _v36 = val1.constraint_region_shape
01151         start = end
01152         end += 1
01153         (_v36.type,) = _struct_b.unpack(str[start:end])
01154         start = end
01155         end += 4
01156         (length,) = _struct_I.unpack(str[start:end])
01157         pattern = '<%sd'%length
01158         start = end
01159         end += struct.calcsize(pattern)
01160         _v36.dimensions = struct.unpack(pattern, str[start:end])
01161         start = end
01162         end += 4
01163         (length,) = _struct_I.unpack(str[start:end])
01164         pattern = '<%si'%length
01165         start = end
01166         end += struct.calcsize(pattern)
01167         _v36.triangles = struct.unpack(pattern, str[start:end])
01168         start = end
01169         end += 4
01170         (length,) = _struct_I.unpack(str[start:end])
01171         _v36.vertices = []
01172         for i in range(0, length):
01173           val3 = geometry_msgs.msg.Point()
01174           _x = val3
01175           start = end
01176           end += 24
01177           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01178           _v36.vertices.append(val3)
01179         _v37 = val1.constraint_region_orientation
01180         _x = _v37
01181         start = end
01182         end += 32
01183         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01184         start = end
01185         end += 8
01186         (val1.weight,) = _struct_d.unpack(str[start:end])
01187         self.goal.path_constraints.position_constraints.append(val1)
01188       start = end
01189       end += 4
01190       (length,) = _struct_I.unpack(str[start:end])
01191       self.goal.path_constraints.orientation_constraints = []
01192       for i in range(0, length):
01193         val1 = arm_navigation_msgs.msg.OrientationConstraint()
01194         _v38 = val1.header
01195         start = end
01196         end += 4
01197         (_v38.seq,) = _struct_I.unpack(str[start:end])
01198         _v39 = _v38.stamp
01199         _x = _v39
01200         start = end
01201         end += 8
01202         (_x.secs, _x.nsecs,) = _struct_2I.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         if python3:
01209           _v38.frame_id = str[start:end].decode('utf-8')
01210         else:
01211           _v38.frame_id = str[start:end]
01212         start = end
01213         end += 4
01214         (length,) = _struct_I.unpack(str[start:end])
01215         start = end
01216         end += length
01217         if python3:
01218           val1.link_name = str[start:end].decode('utf-8')
01219         else:
01220           val1.link_name = str[start:end]
01221         start = end
01222         end += 4
01223         (val1.type,) = _struct_i.unpack(str[start:end])
01224         _v40 = val1.orientation
01225         _x = _v40
01226         start = end
01227         end += 32
01228         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01229         _x = val1
01230         start = end
01231         end += 32
01232         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01233         self.goal.path_constraints.orientation_constraints.append(val1)
01234       start = end
01235       end += 4
01236       (length,) = _struct_I.unpack(str[start:end])
01237       self.goal.path_constraints.visibility_constraints = []
01238       for i in range(0, length):
01239         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01240         _v41 = val1.header
01241         start = end
01242         end += 4
01243         (_v41.seq,) = _struct_I.unpack(str[start:end])
01244         _v42 = _v41.stamp
01245         _x = _v42
01246         start = end
01247         end += 8
01248         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01249         start = end
01250         end += 4
01251         (length,) = _struct_I.unpack(str[start:end])
01252         start = end
01253         end += length
01254         if python3:
01255           _v41.frame_id = str[start:end].decode('utf-8')
01256         else:
01257           _v41.frame_id = str[start:end]
01258         _v43 = val1.target
01259         _v44 = _v43.header
01260         start = end
01261         end += 4
01262         (_v44.seq,) = _struct_I.unpack(str[start:end])
01263         _v45 = _v44.stamp
01264         _x = _v45
01265         start = end
01266         end += 8
01267         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01268         start = end
01269         end += 4
01270         (length,) = _struct_I.unpack(str[start:end])
01271         start = end
01272         end += length
01273         if python3:
01274           _v44.frame_id = str[start:end].decode('utf-8')
01275         else:
01276           _v44.frame_id = str[start:end]
01277         _v46 = _v43.point
01278         _x = _v46
01279         start = end
01280         end += 24
01281         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01282         _v47 = val1.sensor_pose
01283         _v48 = _v47.header
01284         start = end
01285         end += 4
01286         (_v48.seq,) = _struct_I.unpack(str[start:end])
01287         _v49 = _v48.stamp
01288         _x = _v49
01289         start = end
01290         end += 8
01291         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01292         start = end
01293         end += 4
01294         (length,) = _struct_I.unpack(str[start:end])
01295         start = end
01296         end += length
01297         if python3:
01298           _v48.frame_id = str[start:end].decode('utf-8')
01299         else:
01300           _v48.frame_id = str[start:end]
01301         _v50 = _v47.pose
01302         _v51 = _v50.position
01303         _x = _v51
01304         start = end
01305         end += 24
01306         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01307         _v52 = _v50.orientation
01308         _x = _v52
01309         start = end
01310         end += 32
01311         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01312         start = end
01313         end += 8
01314         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01315         self.goal.path_constraints.visibility_constraints.append(val1)
01316       start = end
01317       end += 4
01318       (length,) = _struct_I.unpack(str[start:end])
01319       self.goal.additional_collision_operations.collision_operations = []
01320       for i in range(0, length):
01321         val1 = arm_navigation_msgs.msg.CollisionOperation()
01322         start = end
01323         end += 4
01324         (length,) = _struct_I.unpack(str[start:end])
01325         start = end
01326         end += length
01327         if python3:
01328           val1.object1 = str[start:end].decode('utf-8')
01329         else:
01330           val1.object1 = str[start:end]
01331         start = end
01332         end += 4
01333         (length,) = _struct_I.unpack(str[start:end])
01334         start = end
01335         end += length
01336         if python3:
01337           val1.object2 = str[start:end].decode('utf-8')
01338         else:
01339           val1.object2 = str[start:end]
01340         _x = val1
01341         start = end
01342         end += 12
01343         (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
01344         self.goal.additional_collision_operations.collision_operations.append(val1)
01345       start = end
01346       end += 4
01347       (length,) = _struct_I.unpack(str[start:end])
01348       self.goal.additional_link_padding = []
01349       for i in range(0, length):
01350         val1 = arm_navigation_msgs.msg.LinkPadding()
01351         start = end
01352         end += 4
01353         (length,) = _struct_I.unpack(str[start:end])
01354         start = end
01355         end += length
01356         if python3:
01357           val1.link_name = str[start:end].decode('utf-8')
01358         else:
01359           val1.link_name = str[start:end]
01360         start = end
01361         end += 8
01362         (val1.padding,) = _struct_d.unpack(str[start:end])
01363         self.goal.additional_link_padding.append(val1)
01364       return self
01365     except struct.error as e:
01366       raise genpy.DeserializationError(e) #most likely buffer underfill
01367 
01368 
01369   def serialize_numpy(self, buff, numpy):
01370     """
01371     serialize message with numpy array types into buffer
01372     :param buff: buffer, ``StringIO``
01373     :param numpy: numpy python module
01374     """
01375     try:
01376       _x = self
01377       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
01378       _x = self.header.frame_id
01379       length = len(_x)
01380       if python3 or type(_x) == unicode:
01381         _x = _x.encode('utf-8')
01382         length = len(_x)
01383       buff.write(struct.pack('<I%ss'%length, length, _x))
01384       _x = self
01385       buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
01386       _x = self.goal_id.id
01387       length = len(_x)
01388       if python3 or type(_x) == unicode:
01389         _x = _x.encode('utf-8')
01390         length = len(_x)
01391       buff.write(struct.pack('<I%ss'%length, length, _x))
01392       _x = self.goal.arm_name
01393       length = len(_x)
01394       if python3 or type(_x) == unicode:
01395         _x = _x.encode('utf-8')
01396         length = len(_x)
01397       buff.write(struct.pack('<I%ss'%length, length, _x))
01398       length = len(self.goal.place_locations)
01399       buff.write(_struct_I.pack(length))
01400       for val1 in self.goal.place_locations:
01401         _v53 = val1.header
01402         buff.write(_struct_I.pack(_v53.seq))
01403         _v54 = _v53.stamp
01404         _x = _v54
01405         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01406         _x = _v53.frame_id
01407         length = len(_x)
01408         if python3 or type(_x) == unicode:
01409           _x = _x.encode('utf-8')
01410           length = len(_x)
01411         buff.write(struct.pack('<I%ss'%length, length, _x))
01412         _v55 = val1.pose
01413         _v56 = _v55.position
01414         _x = _v56
01415         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01416         _v57 = _v55.orientation
01417         _x = _v57
01418         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01419       _x = self.goal.grasp.id
01420       length = len(_x)
01421       if python3 or type(_x) == unicode:
01422         _x = _x.encode('utf-8')
01423         length = len(_x)
01424       buff.write(struct.pack('<I%ss'%length, length, _x))
01425       _x = self
01426       buff.write(_struct_3I.pack(_x.goal.grasp.pre_grasp_posture.header.seq, _x.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.goal.grasp.pre_grasp_posture.header.stamp.nsecs))
01427       _x = self.goal.grasp.pre_grasp_posture.header.frame_id
01428       length = len(_x)
01429       if python3 or type(_x) == unicode:
01430         _x = _x.encode('utf-8')
01431         length = len(_x)
01432       buff.write(struct.pack('<I%ss'%length, length, _x))
01433       length = len(self.goal.grasp.pre_grasp_posture.name)
01434       buff.write(_struct_I.pack(length))
01435       for val1 in self.goal.grasp.pre_grasp_posture.name:
01436         length = len(val1)
01437         if python3 or type(val1) == unicode:
01438           val1 = val1.encode('utf-8')
01439           length = len(val1)
01440         buff.write(struct.pack('<I%ss'%length, length, val1))
01441       length = len(self.goal.grasp.pre_grasp_posture.position)
01442       buff.write(_struct_I.pack(length))
01443       pattern = '<%sd'%length
01444       buff.write(self.goal.grasp.pre_grasp_posture.position.tostring())
01445       length = len(self.goal.grasp.pre_grasp_posture.velocity)
01446       buff.write(_struct_I.pack(length))
01447       pattern = '<%sd'%length
01448       buff.write(self.goal.grasp.pre_grasp_posture.velocity.tostring())
01449       length = len(self.goal.grasp.pre_grasp_posture.effort)
01450       buff.write(_struct_I.pack(length))
01451       pattern = '<%sd'%length
01452       buff.write(self.goal.grasp.pre_grasp_posture.effort.tostring())
01453       _x = self
01454       buff.write(_struct_3I.pack(_x.goal.grasp.grasp_posture.header.seq, _x.goal.grasp.grasp_posture.header.stamp.secs, _x.goal.grasp.grasp_posture.header.stamp.nsecs))
01455       _x = self.goal.grasp.grasp_posture.header.frame_id
01456       length = len(_x)
01457       if python3 or type(_x) == unicode:
01458         _x = _x.encode('utf-8')
01459         length = len(_x)
01460       buff.write(struct.pack('<I%ss'%length, length, _x))
01461       length = len(self.goal.grasp.grasp_posture.name)
01462       buff.write(_struct_I.pack(length))
01463       for val1 in self.goal.grasp.grasp_posture.name:
01464         length = len(val1)
01465         if python3 or type(val1) == unicode:
01466           val1 = val1.encode('utf-8')
01467           length = len(val1)
01468         buff.write(struct.pack('<I%ss'%length, length, val1))
01469       length = len(self.goal.grasp.grasp_posture.position)
01470       buff.write(_struct_I.pack(length))
01471       pattern = '<%sd'%length
01472       buff.write(self.goal.grasp.grasp_posture.position.tostring())
01473       length = len(self.goal.grasp.grasp_posture.velocity)
01474       buff.write(_struct_I.pack(length))
01475       pattern = '<%sd'%length
01476       buff.write(self.goal.grasp.grasp_posture.velocity.tostring())
01477       length = len(self.goal.grasp.grasp_posture.effort)
01478       buff.write(_struct_I.pack(length))
01479       pattern = '<%sd'%length
01480       buff.write(self.goal.grasp.grasp_posture.effort.tostring())
01481       _x = self
01482       buff.write(_struct_3I.pack(_x.goal.grasp.grasp_pose.header.seq, _x.goal.grasp.grasp_pose.header.stamp.secs, _x.goal.grasp.grasp_pose.header.stamp.nsecs))
01483       _x = self.goal.grasp.grasp_pose.header.frame_id
01484       length = len(_x)
01485       if python3 or type(_x) == unicode:
01486         _x = _x.encode('utf-8')
01487         length = len(_x)
01488       buff.write(struct.pack('<I%ss'%length, length, _x))
01489       _x = self
01490       buff.write(_struct_8d3I.pack(_x.goal.grasp.grasp_pose.pose.position.x, _x.goal.grasp.grasp_pose.pose.position.y, _x.goal.grasp.grasp_pose.pose.position.z, _x.goal.grasp.grasp_pose.pose.orientation.x, _x.goal.grasp.grasp_pose.pose.orientation.y, _x.goal.grasp.grasp_pose.pose.orientation.z, _x.goal.grasp.grasp_pose.pose.orientation.w, _x.goal.grasp.grasp_quality, _x.goal.grasp.approach.direction.header.seq, _x.goal.grasp.approach.direction.header.stamp.secs, _x.goal.grasp.approach.direction.header.stamp.nsecs))
01491       _x = self.goal.grasp.approach.direction.header.frame_id
01492       length = len(_x)
01493       if python3 or type(_x) == unicode:
01494         _x = _x.encode('utf-8')
01495         length = len(_x)
01496       buff.write(struct.pack('<I%ss'%length, length, _x))
01497       _x = self
01498       buff.write(_struct_3d2f3I.pack(_x.goal.grasp.approach.direction.vector.x, _x.goal.grasp.approach.direction.vector.y, _x.goal.grasp.approach.direction.vector.z, _x.goal.grasp.approach.desired_distance, _x.goal.grasp.approach.min_distance, _x.goal.grasp.retreat.direction.header.seq, _x.goal.grasp.retreat.direction.header.stamp.secs, _x.goal.grasp.retreat.direction.header.stamp.nsecs))
01499       _x = self.goal.grasp.retreat.direction.header.frame_id
01500       length = len(_x)
01501       if python3 or type(_x) == unicode:
01502         _x = _x.encode('utf-8')
01503         length = len(_x)
01504       buff.write(struct.pack('<I%ss'%length, length, _x))
01505       _x = self
01506       buff.write(_struct_3d3f.pack(_x.goal.grasp.retreat.direction.vector.x, _x.goal.grasp.retreat.direction.vector.y, _x.goal.grasp.retreat.direction.vector.z, _x.goal.grasp.retreat.desired_distance, _x.goal.grasp.retreat.min_distance, _x.goal.grasp.max_contact_force))
01507       length = len(self.goal.grasp.allowed_touch_objects)
01508       buff.write(_struct_I.pack(length))
01509       for val1 in self.goal.grasp.allowed_touch_objects:
01510         length = len(val1)
01511         if python3 or type(val1) == unicode:
01512           val1 = val1.encode('utf-8')
01513           length = len(val1)
01514         buff.write(struct.pack('<I%ss'%length, length, val1))
01515       _x = self
01516       buff.write(_struct_2f3I.pack(_x.goal.desired_retreat_distance, _x.goal.min_retreat_distance, _x.goal.approach.direction.header.seq, _x.goal.approach.direction.header.stamp.secs, _x.goal.approach.direction.header.stamp.nsecs))
01517       _x = self.goal.approach.direction.header.frame_id
01518       length = len(_x)
01519       if python3 or type(_x) == unicode:
01520         _x = _x.encode('utf-8')
01521         length = len(_x)
01522       buff.write(struct.pack('<I%ss'%length, length, _x))
01523       _x = self
01524       buff.write(_struct_3d2f.pack(_x.goal.approach.direction.vector.x, _x.goal.approach.direction.vector.y, _x.goal.approach.direction.vector.z, _x.goal.approach.desired_distance, _x.goal.approach.min_distance))
01525       _x = self.goal.collision_object_name
01526       length = len(_x)
01527       if python3 or type(_x) == unicode:
01528         _x = _x.encode('utf-8')
01529         length = len(_x)
01530       buff.write(struct.pack('<I%ss'%length, length, _x))
01531       _x = self.goal.collision_support_surface_name
01532       length = len(_x)
01533       if python3 or type(_x) == unicode:
01534         _x = _x.encode('utf-8')
01535         length = len(_x)
01536       buff.write(struct.pack('<I%ss'%length, length, _x))
01537       _x = self
01538       buff.write(_struct_2BdB.pack(_x.goal.allow_gripper_support_collision, _x.goal.use_reactive_place, _x.goal.place_padding, _x.goal.only_perform_feasibility_test))
01539       length = len(self.goal.path_constraints.joint_constraints)
01540       buff.write(_struct_I.pack(length))
01541       for val1 in self.goal.path_constraints.joint_constraints:
01542         _x = val1.joint_name
01543         length = len(_x)
01544         if python3 or type(_x) == unicode:
01545           _x = _x.encode('utf-8')
01546           length = len(_x)
01547         buff.write(struct.pack('<I%ss'%length, length, _x))
01548         _x = val1
01549         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01550       length = len(self.goal.path_constraints.position_constraints)
01551       buff.write(_struct_I.pack(length))
01552       for val1 in self.goal.path_constraints.position_constraints:
01553         _v58 = val1.header
01554         buff.write(_struct_I.pack(_v58.seq))
01555         _v59 = _v58.stamp
01556         _x = _v59
01557         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01558         _x = _v58.frame_id
01559         length = len(_x)
01560         if python3 or type(_x) == unicode:
01561           _x = _x.encode('utf-8')
01562           length = len(_x)
01563         buff.write(struct.pack('<I%ss'%length, length, _x))
01564         _x = val1.link_name
01565         length = len(_x)
01566         if python3 or type(_x) == unicode:
01567           _x = _x.encode('utf-8')
01568           length = len(_x)
01569         buff.write(struct.pack('<I%ss'%length, length, _x))
01570         _v60 = val1.target_point_offset
01571         _x = _v60
01572         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01573         _v61 = val1.position
01574         _x = _v61
01575         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01576         _v62 = val1.constraint_region_shape
01577         buff.write(_struct_b.pack(_v62.type))
01578         length = len(_v62.dimensions)
01579         buff.write(_struct_I.pack(length))
01580         pattern = '<%sd'%length
01581         buff.write(_v62.dimensions.tostring())
01582         length = len(_v62.triangles)
01583         buff.write(_struct_I.pack(length))
01584         pattern = '<%si'%length
01585         buff.write(_v62.triangles.tostring())
01586         length = len(_v62.vertices)
01587         buff.write(_struct_I.pack(length))
01588         for val3 in _v62.vertices:
01589           _x = val3
01590           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01591         _v63 = val1.constraint_region_orientation
01592         _x = _v63
01593         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01594         buff.write(_struct_d.pack(val1.weight))
01595       length = len(self.goal.path_constraints.orientation_constraints)
01596       buff.write(_struct_I.pack(length))
01597       for val1 in self.goal.path_constraints.orientation_constraints:
01598         _v64 = val1.header
01599         buff.write(_struct_I.pack(_v64.seq))
01600         _v65 = _v64.stamp
01601         _x = _v65
01602         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01603         _x = _v64.frame_id
01604         length = len(_x)
01605         if python3 or type(_x) == unicode:
01606           _x = _x.encode('utf-8')
01607           length = len(_x)
01608         buff.write(struct.pack('<I%ss'%length, length, _x))
01609         _x = val1.link_name
01610         length = len(_x)
01611         if python3 or type(_x) == unicode:
01612           _x = _x.encode('utf-8')
01613           length = len(_x)
01614         buff.write(struct.pack('<I%ss'%length, length, _x))
01615         buff.write(_struct_i.pack(val1.type))
01616         _v66 = val1.orientation
01617         _x = _v66
01618         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01619         _x = val1
01620         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01621       length = len(self.goal.path_constraints.visibility_constraints)
01622       buff.write(_struct_I.pack(length))
01623       for val1 in self.goal.path_constraints.visibility_constraints:
01624         _v67 = val1.header
01625         buff.write(_struct_I.pack(_v67.seq))
01626         _v68 = _v67.stamp
01627         _x = _v68
01628         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01629         _x = _v67.frame_id
01630         length = len(_x)
01631         if python3 or type(_x) == unicode:
01632           _x = _x.encode('utf-8')
01633           length = len(_x)
01634         buff.write(struct.pack('<I%ss'%length, length, _x))
01635         _v69 = val1.target
01636         _v70 = _v69.header
01637         buff.write(_struct_I.pack(_v70.seq))
01638         _v71 = _v70.stamp
01639         _x = _v71
01640         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01641         _x = _v70.frame_id
01642         length = len(_x)
01643         if python3 or type(_x) == unicode:
01644           _x = _x.encode('utf-8')
01645           length = len(_x)
01646         buff.write(struct.pack('<I%ss'%length, length, _x))
01647         _v72 = _v69.point
01648         _x = _v72
01649         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01650         _v73 = val1.sensor_pose
01651         _v74 = _v73.header
01652         buff.write(_struct_I.pack(_v74.seq))
01653         _v75 = _v74.stamp
01654         _x = _v75
01655         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01656         _x = _v74.frame_id
01657         length = len(_x)
01658         if python3 or type(_x) == unicode:
01659           _x = _x.encode('utf-8')
01660           length = len(_x)
01661         buff.write(struct.pack('<I%ss'%length, length, _x))
01662         _v76 = _v73.pose
01663         _v77 = _v76.position
01664         _x = _v77
01665         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01666         _v78 = _v76.orientation
01667         _x = _v78
01668         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01669         buff.write(_struct_d.pack(val1.absolute_tolerance))
01670       length = len(self.goal.additional_collision_operations.collision_operations)
01671       buff.write(_struct_I.pack(length))
01672       for val1 in self.goal.additional_collision_operations.collision_operations:
01673         _x = val1.object1
01674         length = len(_x)
01675         if python3 or type(_x) == unicode:
01676           _x = _x.encode('utf-8')
01677           length = len(_x)
01678         buff.write(struct.pack('<I%ss'%length, length, _x))
01679         _x = val1.object2
01680         length = len(_x)
01681         if python3 or type(_x) == unicode:
01682           _x = _x.encode('utf-8')
01683           length = len(_x)
01684         buff.write(struct.pack('<I%ss'%length, length, _x))
01685         _x = val1
01686         buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
01687       length = len(self.goal.additional_link_padding)
01688       buff.write(_struct_I.pack(length))
01689       for val1 in self.goal.additional_link_padding:
01690         _x = val1.link_name
01691         length = len(_x)
01692         if python3 or type(_x) == unicode:
01693           _x = _x.encode('utf-8')
01694           length = len(_x)
01695         buff.write(struct.pack('<I%ss'%length, length, _x))
01696         buff.write(_struct_d.pack(val1.padding))
01697     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
01698     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
01699 
01700   def deserialize_numpy(self, str, numpy):
01701     """
01702     unpack serialized message in str into this message instance using numpy for array types
01703     :param str: byte array of serialized message, ``str``
01704     :param numpy: numpy python module
01705     """
01706     try:
01707       if self.header is None:
01708         self.header = std_msgs.msg.Header()
01709       if self.goal_id is None:
01710         self.goal_id = actionlib_msgs.msg.GoalID()
01711       if self.goal is None:
01712         self.goal = object_manipulation_msgs.msg.PlaceGoal()
01713       end = 0
01714       _x = self
01715       start = end
01716       end += 12
01717       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01718       start = end
01719       end += 4
01720       (length,) = _struct_I.unpack(str[start:end])
01721       start = end
01722       end += length
01723       if python3:
01724         self.header.frame_id = str[start:end].decode('utf-8')
01725       else:
01726         self.header.frame_id = str[start:end]
01727       _x = self
01728       start = end
01729       end += 8
01730       (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01731       start = end
01732       end += 4
01733       (length,) = _struct_I.unpack(str[start:end])
01734       start = end
01735       end += length
01736       if python3:
01737         self.goal_id.id = str[start:end].decode('utf-8')
01738       else:
01739         self.goal_id.id = str[start:end]
01740       start = end
01741       end += 4
01742       (length,) = _struct_I.unpack(str[start:end])
01743       start = end
01744       end += length
01745       if python3:
01746         self.goal.arm_name = str[start:end].decode('utf-8')
01747       else:
01748         self.goal.arm_name = str[start:end]
01749       start = end
01750       end += 4
01751       (length,) = _struct_I.unpack(str[start:end])
01752       self.goal.place_locations = []
01753       for i in range(0, length):
01754         val1 = geometry_msgs.msg.PoseStamped()
01755         _v79 = val1.header
01756         start = end
01757         end += 4
01758         (_v79.seq,) = _struct_I.unpack(str[start:end])
01759         _v80 = _v79.stamp
01760         _x = _v80
01761         start = end
01762         end += 8
01763         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01764         start = end
01765         end += 4
01766         (length,) = _struct_I.unpack(str[start:end])
01767         start = end
01768         end += length
01769         if python3:
01770           _v79.frame_id = str[start:end].decode('utf-8')
01771         else:
01772           _v79.frame_id = str[start:end]
01773         _v81 = val1.pose
01774         _v82 = _v81.position
01775         _x = _v82
01776         start = end
01777         end += 24
01778         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01779         _v83 = _v81.orientation
01780         _x = _v83
01781         start = end
01782         end += 32
01783         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01784         self.goal.place_locations.append(val1)
01785       start = end
01786       end += 4
01787       (length,) = _struct_I.unpack(str[start:end])
01788       start = end
01789       end += length
01790       if python3:
01791         self.goal.grasp.id = str[start:end].decode('utf-8')
01792       else:
01793         self.goal.grasp.id = str[start:end]
01794       _x = self
01795       start = end
01796       end += 12
01797       (_x.goal.grasp.pre_grasp_posture.header.seq, _x.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.goal.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01798       start = end
01799       end += 4
01800       (length,) = _struct_I.unpack(str[start:end])
01801       start = end
01802       end += length
01803       if python3:
01804         self.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end].decode('utf-8')
01805       else:
01806         self.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end]
01807       start = end
01808       end += 4
01809       (length,) = _struct_I.unpack(str[start:end])
01810       self.goal.grasp.pre_grasp_posture.name = []
01811       for i in range(0, length):
01812         start = end
01813         end += 4
01814         (length,) = _struct_I.unpack(str[start:end])
01815         start = end
01816         end += length
01817         if python3:
01818           val1 = str[start:end].decode('utf-8')
01819         else:
01820           val1 = str[start:end]
01821         self.goal.grasp.pre_grasp_posture.name.append(val1)
01822       start = end
01823       end += 4
01824       (length,) = _struct_I.unpack(str[start:end])
01825       pattern = '<%sd'%length
01826       start = end
01827       end += struct.calcsize(pattern)
01828       self.goal.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01829       start = end
01830       end += 4
01831       (length,) = _struct_I.unpack(str[start:end])
01832       pattern = '<%sd'%length
01833       start = end
01834       end += struct.calcsize(pattern)
01835       self.goal.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01836       start = end
01837       end += 4
01838       (length,) = _struct_I.unpack(str[start:end])
01839       pattern = '<%sd'%length
01840       start = end
01841       end += struct.calcsize(pattern)
01842       self.goal.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01843       _x = self
01844       start = end
01845       end += 12
01846       (_x.goal.grasp.grasp_posture.header.seq, _x.goal.grasp.grasp_posture.header.stamp.secs, _x.goal.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01847       start = end
01848       end += 4
01849       (length,) = _struct_I.unpack(str[start:end])
01850       start = end
01851       end += length
01852       if python3:
01853         self.goal.grasp.grasp_posture.header.frame_id = str[start:end].decode('utf-8')
01854       else:
01855         self.goal.grasp.grasp_posture.header.frame_id = str[start:end]
01856       start = end
01857       end += 4
01858       (length,) = _struct_I.unpack(str[start:end])
01859       self.goal.grasp.grasp_posture.name = []
01860       for i in range(0, length):
01861         start = end
01862         end += 4
01863         (length,) = _struct_I.unpack(str[start:end])
01864         start = end
01865         end += length
01866         if python3:
01867           val1 = str[start:end].decode('utf-8')
01868         else:
01869           val1 = str[start:end]
01870         self.goal.grasp.grasp_posture.name.append(val1)
01871       start = end
01872       end += 4
01873       (length,) = _struct_I.unpack(str[start:end])
01874       pattern = '<%sd'%length
01875       start = end
01876       end += struct.calcsize(pattern)
01877       self.goal.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01878       start = end
01879       end += 4
01880       (length,) = _struct_I.unpack(str[start:end])
01881       pattern = '<%sd'%length
01882       start = end
01883       end += struct.calcsize(pattern)
01884       self.goal.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01885       start = end
01886       end += 4
01887       (length,) = _struct_I.unpack(str[start:end])
01888       pattern = '<%sd'%length
01889       start = end
01890       end += struct.calcsize(pattern)
01891       self.goal.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01892       _x = self
01893       start = end
01894       end += 12
01895       (_x.goal.grasp.grasp_pose.header.seq, _x.goal.grasp.grasp_pose.header.stamp.secs, _x.goal.grasp.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01896       start = end
01897       end += 4
01898       (length,) = _struct_I.unpack(str[start:end])
01899       start = end
01900       end += length
01901       if python3:
01902         self.goal.grasp.grasp_pose.header.frame_id = str[start:end].decode('utf-8')
01903       else:
01904         self.goal.grasp.grasp_pose.header.frame_id = str[start:end]
01905       _x = self
01906       start = end
01907       end += 76
01908       (_x.goal.grasp.grasp_pose.pose.position.x, _x.goal.grasp.grasp_pose.pose.position.y, _x.goal.grasp.grasp_pose.pose.position.z, _x.goal.grasp.grasp_pose.pose.orientation.x, _x.goal.grasp.grasp_pose.pose.orientation.y, _x.goal.grasp.grasp_pose.pose.orientation.z, _x.goal.grasp.grasp_pose.pose.orientation.w, _x.goal.grasp.grasp_quality, _x.goal.grasp.approach.direction.header.seq, _x.goal.grasp.approach.direction.header.stamp.secs, _x.goal.grasp.approach.direction.header.stamp.nsecs,) = _struct_8d3I.unpack(str[start:end])
01909       start = end
01910       end += 4
01911       (length,) = _struct_I.unpack(str[start:end])
01912       start = end
01913       end += length
01914       if python3:
01915         self.goal.grasp.approach.direction.header.frame_id = str[start:end].decode('utf-8')
01916       else:
01917         self.goal.grasp.approach.direction.header.frame_id = str[start:end]
01918       _x = self
01919       start = end
01920       end += 44
01921       (_x.goal.grasp.approach.direction.vector.x, _x.goal.grasp.approach.direction.vector.y, _x.goal.grasp.approach.direction.vector.z, _x.goal.grasp.approach.desired_distance, _x.goal.grasp.approach.min_distance, _x.goal.grasp.retreat.direction.header.seq, _x.goal.grasp.retreat.direction.header.stamp.secs, _x.goal.grasp.retreat.direction.header.stamp.nsecs,) = _struct_3d2f3I.unpack(str[start:end])
01922       start = end
01923       end += 4
01924       (length,) = _struct_I.unpack(str[start:end])
01925       start = end
01926       end += length
01927       if python3:
01928         self.goal.grasp.retreat.direction.header.frame_id = str[start:end].decode('utf-8')
01929       else:
01930         self.goal.grasp.retreat.direction.header.frame_id = str[start:end]
01931       _x = self
01932       start = end
01933       end += 36
01934       (_x.goal.grasp.retreat.direction.vector.x, _x.goal.grasp.retreat.direction.vector.y, _x.goal.grasp.retreat.direction.vector.z, _x.goal.grasp.retreat.desired_distance, _x.goal.grasp.retreat.min_distance, _x.goal.grasp.max_contact_force,) = _struct_3d3f.unpack(str[start:end])
01935       start = end
01936       end += 4
01937       (length,) = _struct_I.unpack(str[start:end])
01938       self.goal.grasp.allowed_touch_objects = []
01939       for i in range(0, length):
01940         start = end
01941         end += 4
01942         (length,) = _struct_I.unpack(str[start:end])
01943         start = end
01944         end += length
01945         if python3:
01946           val1 = str[start:end].decode('utf-8')
01947         else:
01948           val1 = str[start:end]
01949         self.goal.grasp.allowed_touch_objects.append(val1)
01950       _x = self
01951       start = end
01952       end += 20
01953       (_x.goal.desired_retreat_distance, _x.goal.min_retreat_distance, _x.goal.approach.direction.header.seq, _x.goal.approach.direction.header.stamp.secs, _x.goal.approach.direction.header.stamp.nsecs,) = _struct_2f3I.unpack(str[start:end])
01954       start = end
01955       end += 4
01956       (length,) = _struct_I.unpack(str[start:end])
01957       start = end
01958       end += length
01959       if python3:
01960         self.goal.approach.direction.header.frame_id = str[start:end].decode('utf-8')
01961       else:
01962         self.goal.approach.direction.header.frame_id = str[start:end]
01963       _x = self
01964       start = end
01965       end += 32
01966       (_x.goal.approach.direction.vector.x, _x.goal.approach.direction.vector.y, _x.goal.approach.direction.vector.z, _x.goal.approach.desired_distance, _x.goal.approach.min_distance,) = _struct_3d2f.unpack(str[start:end])
01967       start = end
01968       end += 4
01969       (length,) = _struct_I.unpack(str[start:end])
01970       start = end
01971       end += length
01972       if python3:
01973         self.goal.collision_object_name = str[start:end].decode('utf-8')
01974       else:
01975         self.goal.collision_object_name = str[start:end]
01976       start = end
01977       end += 4
01978       (length,) = _struct_I.unpack(str[start:end])
01979       start = end
01980       end += length
01981       if python3:
01982         self.goal.collision_support_surface_name = str[start:end].decode('utf-8')
01983       else:
01984         self.goal.collision_support_surface_name = str[start:end]
01985       _x = self
01986       start = end
01987       end += 11
01988       (_x.goal.allow_gripper_support_collision, _x.goal.use_reactive_place, _x.goal.place_padding, _x.goal.only_perform_feasibility_test,) = _struct_2BdB.unpack(str[start:end])
01989       self.goal.allow_gripper_support_collision = bool(self.goal.allow_gripper_support_collision)
01990       self.goal.use_reactive_place = bool(self.goal.use_reactive_place)
01991       self.goal.only_perform_feasibility_test = bool(self.goal.only_perform_feasibility_test)
01992       start = end
01993       end += 4
01994       (length,) = _struct_I.unpack(str[start:end])
01995       self.goal.path_constraints.joint_constraints = []
01996       for i in range(0, length):
01997         val1 = arm_navigation_msgs.msg.JointConstraint()
01998         start = end
01999         end += 4
02000         (length,) = _struct_I.unpack(str[start:end])
02001         start = end
02002         end += length
02003         if python3:
02004           val1.joint_name = str[start:end].decode('utf-8')
02005         else:
02006           val1.joint_name = str[start:end]
02007         _x = val1
02008         start = end
02009         end += 32
02010         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02011         self.goal.path_constraints.joint_constraints.append(val1)
02012       start = end
02013       end += 4
02014       (length,) = _struct_I.unpack(str[start:end])
02015       self.goal.path_constraints.position_constraints = []
02016       for i in range(0, length):
02017         val1 = arm_navigation_msgs.msg.PositionConstraint()
02018         _v84 = val1.header
02019         start = end
02020         end += 4
02021         (_v84.seq,) = _struct_I.unpack(str[start:end])
02022         _v85 = _v84.stamp
02023         _x = _v85
02024         start = end
02025         end += 8
02026         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02027         start = end
02028         end += 4
02029         (length,) = _struct_I.unpack(str[start:end])
02030         start = end
02031         end += length
02032         if python3:
02033           _v84.frame_id = str[start:end].decode('utf-8')
02034         else:
02035           _v84.frame_id = str[start:end]
02036         start = end
02037         end += 4
02038         (length,) = _struct_I.unpack(str[start:end])
02039         start = end
02040         end += length
02041         if python3:
02042           val1.link_name = str[start:end].decode('utf-8')
02043         else:
02044           val1.link_name = str[start:end]
02045         _v86 = val1.target_point_offset
02046         _x = _v86
02047         start = end
02048         end += 24
02049         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02050         _v87 = val1.position
02051         _x = _v87
02052         start = end
02053         end += 24
02054         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02055         _v88 = val1.constraint_region_shape
02056         start = end
02057         end += 1
02058         (_v88.type,) = _struct_b.unpack(str[start:end])
02059         start = end
02060         end += 4
02061         (length,) = _struct_I.unpack(str[start:end])
02062         pattern = '<%sd'%length
02063         start = end
02064         end += struct.calcsize(pattern)
02065         _v88.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02066         start = end
02067         end += 4
02068         (length,) = _struct_I.unpack(str[start:end])
02069         pattern = '<%si'%length
02070         start = end
02071         end += struct.calcsize(pattern)
02072         _v88.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02073         start = end
02074         end += 4
02075         (length,) = _struct_I.unpack(str[start:end])
02076         _v88.vertices = []
02077         for i in range(0, length):
02078           val3 = geometry_msgs.msg.Point()
02079           _x = val3
02080           start = end
02081           end += 24
02082           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02083           _v88.vertices.append(val3)
02084         _v89 = val1.constraint_region_orientation
02085         _x = _v89
02086         start = end
02087         end += 32
02088         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02089         start = end
02090         end += 8
02091         (val1.weight,) = _struct_d.unpack(str[start:end])
02092         self.goal.path_constraints.position_constraints.append(val1)
02093       start = end
02094       end += 4
02095       (length,) = _struct_I.unpack(str[start:end])
02096       self.goal.path_constraints.orientation_constraints = []
02097       for i in range(0, length):
02098         val1 = arm_navigation_msgs.msg.OrientationConstraint()
02099         _v90 = val1.header
02100         start = end
02101         end += 4
02102         (_v90.seq,) = _struct_I.unpack(str[start:end])
02103         _v91 = _v90.stamp
02104         _x = _v91
02105         start = end
02106         end += 8
02107         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02108         start = end
02109         end += 4
02110         (length,) = _struct_I.unpack(str[start:end])
02111         start = end
02112         end += length
02113         if python3:
02114           _v90.frame_id = str[start:end].decode('utf-8')
02115         else:
02116           _v90.frame_id = str[start:end]
02117         start = end
02118         end += 4
02119         (length,) = _struct_I.unpack(str[start:end])
02120         start = end
02121         end += length
02122         if python3:
02123           val1.link_name = str[start:end].decode('utf-8')
02124         else:
02125           val1.link_name = str[start:end]
02126         start = end
02127         end += 4
02128         (val1.type,) = _struct_i.unpack(str[start:end])
02129         _v92 = val1.orientation
02130         _x = _v92
02131         start = end
02132         end += 32
02133         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02134         _x = val1
02135         start = end
02136         end += 32
02137         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02138         self.goal.path_constraints.orientation_constraints.append(val1)
02139       start = end
02140       end += 4
02141       (length,) = _struct_I.unpack(str[start:end])
02142       self.goal.path_constraints.visibility_constraints = []
02143       for i in range(0, length):
02144         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02145         _v93 = val1.header
02146         start = end
02147         end += 4
02148         (_v93.seq,) = _struct_I.unpack(str[start:end])
02149         _v94 = _v93.stamp
02150         _x = _v94
02151         start = end
02152         end += 8
02153         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02154         start = end
02155         end += 4
02156         (length,) = _struct_I.unpack(str[start:end])
02157         start = end
02158         end += length
02159         if python3:
02160           _v93.frame_id = str[start:end].decode('utf-8')
02161         else:
02162           _v93.frame_id = str[start:end]
02163         _v95 = val1.target
02164         _v96 = _v95.header
02165         start = end
02166         end += 4
02167         (_v96.seq,) = _struct_I.unpack(str[start:end])
02168         _v97 = _v96.stamp
02169         _x = _v97
02170         start = end
02171         end += 8
02172         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02173         start = end
02174         end += 4
02175         (length,) = _struct_I.unpack(str[start:end])
02176         start = end
02177         end += length
02178         if python3:
02179           _v96.frame_id = str[start:end].decode('utf-8')
02180         else:
02181           _v96.frame_id = str[start:end]
02182         _v98 = _v95.point
02183         _x = _v98
02184         start = end
02185         end += 24
02186         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02187         _v99 = val1.sensor_pose
02188         _v100 = _v99.header
02189         start = end
02190         end += 4
02191         (_v100.seq,) = _struct_I.unpack(str[start:end])
02192         _v101 = _v100.stamp
02193         _x = _v101
02194         start = end
02195         end += 8
02196         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02197         start = end
02198         end += 4
02199         (length,) = _struct_I.unpack(str[start:end])
02200         start = end
02201         end += length
02202         if python3:
02203           _v100.frame_id = str[start:end].decode('utf-8')
02204         else:
02205           _v100.frame_id = str[start:end]
02206         _v102 = _v99.pose
02207         _v103 = _v102.position
02208         _x = _v103
02209         start = end
02210         end += 24
02211         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02212         _v104 = _v102.orientation
02213         _x = _v104
02214         start = end
02215         end += 32
02216         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02217         start = end
02218         end += 8
02219         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02220         self.goal.path_constraints.visibility_constraints.append(val1)
02221       start = end
02222       end += 4
02223       (length,) = _struct_I.unpack(str[start:end])
02224       self.goal.additional_collision_operations.collision_operations = []
02225       for i in range(0, length):
02226         val1 = arm_navigation_msgs.msg.CollisionOperation()
02227         start = end
02228         end += 4
02229         (length,) = _struct_I.unpack(str[start:end])
02230         start = end
02231         end += length
02232         if python3:
02233           val1.object1 = str[start:end].decode('utf-8')
02234         else:
02235           val1.object1 = str[start:end]
02236         start = end
02237         end += 4
02238         (length,) = _struct_I.unpack(str[start:end])
02239         start = end
02240         end += length
02241         if python3:
02242           val1.object2 = str[start:end].decode('utf-8')
02243         else:
02244           val1.object2 = str[start:end]
02245         _x = val1
02246         start = end
02247         end += 12
02248         (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
02249         self.goal.additional_collision_operations.collision_operations.append(val1)
02250       start = end
02251       end += 4
02252       (length,) = _struct_I.unpack(str[start:end])
02253       self.goal.additional_link_padding = []
02254       for i in range(0, length):
02255         val1 = arm_navigation_msgs.msg.LinkPadding()
02256         start = end
02257         end += 4
02258         (length,) = _struct_I.unpack(str[start:end])
02259         start = end
02260         end += length
02261         if python3:
02262           val1.link_name = str[start:end].decode('utf-8')
02263         else:
02264           val1.link_name = str[start:end]
02265         start = end
02266         end += 8
02267         (val1.padding,) = _struct_d.unpack(str[start:end])
02268         self.goal.additional_link_padding.append(val1)
02269       return self
02270     except struct.error as e:
02271       raise genpy.DeserializationError(e) #most likely buffer underfill
02272 
02273 _struct_I = genpy.struct_I
02274 _struct_b = struct.Struct("<b")
02275 _struct_2f3I = struct.Struct("<2f3I")
02276 _struct_d = struct.Struct("<d")
02277 _struct_di = struct.Struct("<di")
02278 _struct_i = struct.Struct("<i")
02279 _struct_3d2f = struct.Struct("<3d2f")
02280 _struct_3d3f = struct.Struct("<3d3f")
02281 _struct_8d3I = struct.Struct("<8d3I")
02282 _struct_3I = struct.Struct("<3I")
02283 _struct_2BdB = struct.Struct("<2BdB")
02284 _struct_3d2f3I = struct.Struct("<3d2f3I")
02285 _struct_4d = struct.Struct("<4d")
02286 _struct_2I = struct.Struct("<2I")
02287 _struct_3d = struct.Struct("<3d")


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