00001 """autogenerated by genpy from arm_navigation_msgs/MoveArmActionGoal.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 actionlib_msgs.msg
00009 import geometry_msgs.msg
00010 import sensor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013
00014 class MoveArmActionGoal(genpy.Message):
00015 _md5sum = "d560cc046d6b5e8bf3f70a960054d6c6"
00016 _type = "arm_navigation_msgs/MoveArmActionGoal"
00017 _has_header = True
00018 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019
00020 Header header
00021 actionlib_msgs/GoalID goal_id
00022 MoveArmGoal goal
00023
00024 ================================================================================
00025 MSG: std_msgs/Header
00026 # Standard metadata for higher-level stamped data types.
00027 # This is generally used to communicate timestamped data
00028 # in a particular coordinate frame.
00029 #
00030 # sequence ID: consecutively increasing ID
00031 uint32 seq
00032 #Two-integer timestamp that is expressed as:
00033 # * stamp.secs: seconds (stamp_secs) since epoch
00034 # * stamp.nsecs: nanoseconds since stamp_secs
00035 # time-handling sugar is provided by the client library
00036 time stamp
00037 #Frame this data is associated with
00038 # 0: no frame
00039 # 1: global frame
00040 string frame_id
00041
00042 ================================================================================
00043 MSG: actionlib_msgs/GoalID
00044 # The stamp should store the time at which this goal was requested.
00045 # It is used by an action server when it tries to preempt all
00046 # goals that were requested before a certain time
00047 time stamp
00048
00049 # The id provides a way to associate feedback and
00050 # result message with specific goal requests. The id
00051 # specified must be unique.
00052 string id
00053
00054
00055 ================================================================================
00056 MSG: arm_navigation_msgs/MoveArmGoal
00057 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00058 # Service name to call for getting a motion plan
00059 # Move arm will call a service on this service name
00060 # using the MotionPlanRequest specified here
00061 string planner_service_name
00062
00063 # A planning scene diff
00064 PlanningScene planning_scene_diff
00065
00066 # A motion planning request
00067 MotionPlanRequest motion_plan_request
00068
00069 # OPTIONAL: Diff uses ordered collision operations in addition to allowed_collision_matrix
00070 arm_navigation_msgs/OrderedCollisionOperations operations
00071
00072 # OPTIONAL flag
00073 # Setting this flag to true will allow move_arm to accept plans that do not go all the way to the goal
00074 bool accept_partial_plans
00075
00076 # OPTIONAL flag
00077 # Setting this flag to true will allow move_arm to accept invalid goals
00078 # This is useful if you are using a planner like CHOMP along with a noisy rapidly changing collision map
00079 # and you would like to plan to a goal near an object.
00080 bool accept_invalid_goals
00081
00082 # OPTIONAL flag
00083 # Setting this flag to true will disable the call to IK for a pose goal
00084 bool disable_ik
00085
00086 # OPTIONAL flag
00087 # Setting this flag to true will disable collision monitoring during execution of a trajectory
00088 bool disable_collision_monitoring
00089
00090 ================================================================================
00091 MSG: arm_navigation_msgs/PlanningScene
00092 #full robot state
00093 arm_navigation_msgs/RobotState robot_state
00094
00095 #additional frames for duplicating tf
00096 geometry_msgs/TransformStamped[] fixed_frame_transforms
00097
00098 #full allowed collision matrix
00099 AllowedCollisionMatrix allowed_collision_matrix
00100
00101 #allowed contacts
00102 arm_navigation_msgs/AllowedContactSpecification[] allowed_contacts
00103
00104 #all link paddings
00105 arm_navigation_msgs/LinkPadding[] link_padding
00106
00107 #collision objects
00108 arm_navigation_msgs/CollisionObject[] collision_objects
00109 arm_navigation_msgs/AttachedCollisionObject[] attached_collision_objects
00110
00111 #the collision map
00112 arm_navigation_msgs/CollisionMap collision_map
00113
00114 ================================================================================
00115 MSG: arm_navigation_msgs/RobotState
00116 # This message contains information about the robot state, i.e. the positions of its joints and links
00117 sensor_msgs/JointState joint_state
00118 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00119
00120 ================================================================================
00121 MSG: sensor_msgs/JointState
00122 # This is a message that holds data to describe the state of a set of torque controlled joints.
00123 #
00124 # The state of each joint (revolute or prismatic) is defined by:
00125 # * the position of the joint (rad or m),
00126 # * the velocity of the joint (rad/s or m/s) and
00127 # * the effort that is applied in the joint (Nm or N).
00128 #
00129 # Each joint is uniquely identified by its name
00130 # The header specifies the time at which the joint states were recorded. All the joint states
00131 # in one message have to be recorded at the same time.
00132 #
00133 # This message consists of a multiple arrays, one for each part of the joint state.
00134 # The goal is to make each of the fields optional. When e.g. your joints have no
00135 # effort associated with them, you can leave the effort array empty.
00136 #
00137 # All arrays in this message should have the same size, or be empty.
00138 # This is the only way to uniquely associate the joint name with the correct
00139 # states.
00140
00141
00142 Header header
00143
00144 string[] name
00145 float64[] position
00146 float64[] velocity
00147 float64[] effort
00148
00149 ================================================================================
00150 MSG: arm_navigation_msgs/MultiDOFJointState
00151 #A representation of a multi-dof joint state
00152 time stamp
00153 string[] joint_names
00154 string[] frame_ids
00155 string[] child_frame_ids
00156 geometry_msgs/Pose[] poses
00157
00158 ================================================================================
00159 MSG: geometry_msgs/Pose
00160 # A representation of pose in free space, composed of postion and orientation.
00161 Point position
00162 Quaternion orientation
00163
00164 ================================================================================
00165 MSG: geometry_msgs/Point
00166 # This contains the position of a point in free space
00167 float64 x
00168 float64 y
00169 float64 z
00170
00171 ================================================================================
00172 MSG: geometry_msgs/Quaternion
00173 # This represents an orientation in free space in quaternion form.
00174
00175 float64 x
00176 float64 y
00177 float64 z
00178 float64 w
00179
00180 ================================================================================
00181 MSG: geometry_msgs/TransformStamped
00182 # This expresses a transform from coordinate frame header.frame_id
00183 # to the coordinate frame child_frame_id
00184 #
00185 # This message is mostly used by the
00186 # <a href="http://www.ros.org/wiki/tf">tf</a> package.
00187 # See its documentation for more information.
00188
00189 Header header
00190 string child_frame_id # the frame id of the child frame
00191 Transform transform
00192
00193 ================================================================================
00194 MSG: geometry_msgs/Transform
00195 # This represents the transform between two coordinate frames in free space.
00196
00197 Vector3 translation
00198 Quaternion rotation
00199
00200 ================================================================================
00201 MSG: geometry_msgs/Vector3
00202 # This represents a vector in free space.
00203
00204 float64 x
00205 float64 y
00206 float64 z
00207 ================================================================================
00208 MSG: arm_navigation_msgs/AllowedCollisionMatrix
00209 # the list of link names in the matrix
00210 string[] link_names
00211
00212 # the individual entries in the allowed collision matrix
00213 # symmetric, with same order as link_names
00214 AllowedCollisionEntry[] entries
00215
00216 ================================================================================
00217 MSG: arm_navigation_msgs/AllowedCollisionEntry
00218 # whether or not collision checking is enabled
00219 bool[] enabled
00220
00221 ================================================================================
00222 MSG: arm_navigation_msgs/AllowedContactSpecification
00223 # The names of the regions
00224 string name
00225
00226 # The shape of the region in the environment
00227 arm_navigation_msgs/Shape shape
00228
00229 # The pose of the space defining the region
00230 geometry_msgs/PoseStamped pose_stamped
00231
00232 # The set of links that will be allowed to have penetration contact within this region
00233 string[] link_names
00234
00235 # The maximum penetration depth allowed for every link
00236 float64 penetration_depth
00237
00238 ================================================================================
00239 MSG: arm_navigation_msgs/Shape
00240 byte SPHERE=0
00241 byte BOX=1
00242 byte CYLINDER=2
00243 byte MESH=3
00244
00245 byte type
00246
00247
00248 #### define sphere, box, cylinder ####
00249 # the origin of each shape is considered at the shape's center
00250
00251 # for sphere
00252 # radius := dimensions[0]
00253
00254 # for cylinder
00255 # radius := dimensions[0]
00256 # length := dimensions[1]
00257 # the length is along the Z axis
00258
00259 # for box
00260 # size_x := dimensions[0]
00261 # size_y := dimensions[1]
00262 # size_z := dimensions[2]
00263 float64[] dimensions
00264
00265
00266 #### define mesh ####
00267
00268 # list of triangles; triangle k is defined by tre vertices located
00269 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00270 int32[] triangles
00271 geometry_msgs/Point[] vertices
00272
00273 ================================================================================
00274 MSG: geometry_msgs/PoseStamped
00275 # A Pose with reference coordinate frame and timestamp
00276 Header header
00277 Pose pose
00278
00279 ================================================================================
00280 MSG: arm_navigation_msgs/LinkPadding
00281 #name for the link
00282 string link_name
00283
00284 # padding to apply to the link
00285 float64 padding
00286
00287 ================================================================================
00288 MSG: arm_navigation_msgs/CollisionObject
00289 # a header, used for interpreting the poses
00290 Header header
00291
00292 # the id of the object
00293 string id
00294
00295 # The padding used for filtering points near the object.
00296 # This does not affect collision checking for the object.
00297 # Set to negative to get zero padding.
00298 float32 padding
00299
00300 #This contains what is to be done with the object
00301 CollisionObjectOperation operation
00302
00303 #the shapes associated with the object
00304 arm_navigation_msgs/Shape[] shapes
00305
00306 #the poses associated with the shapes - will be transformed using the header
00307 geometry_msgs/Pose[] poses
00308
00309 ================================================================================
00310 MSG: arm_navigation_msgs/CollisionObjectOperation
00311 #Puts the object into the environment
00312 #or updates the object if already added
00313 byte ADD=0
00314
00315 #Removes the object from the environment entirely
00316 byte REMOVE=1
00317
00318 #Only valid within the context of a CollisionAttachedObject message
00319 #Will be ignored if sent with an CollisionObject message
00320 #Takes an attached object, detaches from the attached link
00321 #But adds back in as regular object
00322 byte DETACH_AND_ADD_AS_OBJECT=2
00323
00324 #Only valid within the context of a CollisionAttachedObject message
00325 #Will be ignored if sent with an CollisionObject message
00326 #Takes current object in the environment and removes it as
00327 #a regular object
00328 byte ATTACH_AND_REMOVE_AS_OBJECT=3
00329
00330 # Byte code for operation
00331 byte operation
00332
00333 ================================================================================
00334 MSG: arm_navigation_msgs/AttachedCollisionObject
00335 # The CollisionObject will be attached with a fixed joint to this link
00336 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation
00337 # is set to REMOVE will remove all attached bodies attached to any object
00338 string link_name
00339
00340 #Reserved for indicating that all attached objects should be removed
00341 string REMOVE_ALL_ATTACHED_OBJECTS = "all"
00342
00343 #This contains the actual shapes and poses for the CollisionObject
00344 #to be attached to the link
00345 #If action is remove and no object.id is set, all objects
00346 #attached to the link indicated by link_name will be removed
00347 CollisionObject object
00348
00349 # The set of links that the attached objects are allowed to touch
00350 # by default - the link_name is included by default
00351 string[] touch_links
00352
00353 ================================================================================
00354 MSG: arm_navigation_msgs/CollisionMap
00355 #header for interpreting box positions
00356 Header header
00357
00358 #boxes for use in collision testing
00359 OrientedBoundingBox[] boxes
00360
00361 ================================================================================
00362 MSG: arm_navigation_msgs/OrientedBoundingBox
00363 #the center of the box
00364 geometry_msgs/Point32 center
00365
00366 #the extents of the box, assuming the center is at the point
00367 geometry_msgs/Point32 extents
00368
00369 #the axis of the box
00370 geometry_msgs/Point32 axis
00371
00372 #the angle of rotation around the axis
00373 float32 angle
00374
00375 ================================================================================
00376 MSG: geometry_msgs/Point32
00377 # This contains the position of a point in free space(with 32 bits of precision).
00378 # It is recommeded to use Point wherever possible instead of Point32.
00379 #
00380 # This recommendation is to promote interoperability.
00381 #
00382 # This message is designed to take up less space when sending
00383 # lots of points at once, as in the case of a PointCloud.
00384
00385 float32 x
00386 float32 y
00387 float32 z
00388 ================================================================================
00389 MSG: arm_navigation_msgs/MotionPlanRequest
00390 # This service contains the definition for a request to the motion
00391 # planner and the output it provides
00392
00393 # Parameters for the workspace that the planner should work inside
00394 arm_navigation_msgs/WorkspaceParameters workspace_parameters
00395
00396 # Starting state updates. If certain joints should be considered
00397 # at positions other than the current ones, these positions should
00398 # be set here
00399 arm_navigation_msgs/RobotState start_state
00400
00401 # The goal state for the model to plan for. The goal is achieved
00402 # if all constraints are satisfied
00403 arm_navigation_msgs/Constraints goal_constraints
00404
00405 # No state at any point along the path in the produced motion plan will violate these constraints
00406 arm_navigation_msgs/Constraints path_constraints
00407
00408 # The name of the motion planner to use. If no name is specified,
00409 # a default motion planner will be used
00410 string planner_id
00411
00412 # The name of the group of joints on which this planner is operating
00413 string group_name
00414
00415 # The number of times this plan is to be computed. Shortest solution
00416 # will be reported.
00417 int32 num_planning_attempts
00418
00419 # The maximum amount of time the motion planner is allowed to plan for
00420 duration allowed_planning_time
00421
00422 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns
00423 duration expected_path_duration
00424 duration expected_path_dt
00425
00426 ================================================================================
00427 MSG: arm_navigation_msgs/WorkspaceParameters
00428 # This message contains a set of parameters useful in
00429 # setting up the workspace for planning
00430 arm_navigation_msgs/Shape workspace_region_shape
00431 geometry_msgs/PoseStamped workspace_region_pose
00432
00433
00434 ================================================================================
00435 MSG: arm_navigation_msgs/Constraints
00436 # This message contains a list of motion planning constraints.
00437
00438 arm_navigation_msgs/JointConstraint[] joint_constraints
00439 arm_navigation_msgs/PositionConstraint[] position_constraints
00440 arm_navigation_msgs/OrientationConstraint[] orientation_constraints
00441 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints
00442
00443 ================================================================================
00444 MSG: arm_navigation_msgs/JointConstraint
00445 # Constrain the position of a joint to be within a certain bound
00446 string joint_name
00447
00448 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00449 float64 position
00450 float64 tolerance_above
00451 float64 tolerance_below
00452
00453 # A weighting factor for this constraint
00454 float64 weight
00455 ================================================================================
00456 MSG: arm_navigation_msgs/PositionConstraint
00457 # This message contains the definition of a position constraint.
00458 Header header
00459
00460 # The robot link this constraint refers to
00461 string link_name
00462
00463 # The offset (in the link frame) for the target point on the link we are planning for
00464 geometry_msgs/Point target_point_offset
00465
00466 # The nominal/target position for the point we are planning for
00467 geometry_msgs/Point position
00468
00469 # The shape of the bounded region that constrains the position of the end-effector
00470 # This region is always centered at the position defined above
00471 arm_navigation_msgs/Shape constraint_region_shape
00472
00473 # The orientation of the bounded region that constrains the position of the end-effector.
00474 # This allows the specification of non-axis aligned constraints
00475 geometry_msgs/Quaternion constraint_region_orientation
00476
00477 # Constraint weighting factor - a weight for this constraint
00478 float64 weight
00479
00480 ================================================================================
00481 MSG: arm_navigation_msgs/OrientationConstraint
00482 # This message contains the definition of an orientation constraint.
00483 Header header
00484
00485 # The robot link this constraint refers to
00486 string link_name
00487
00488 # The type of the constraint
00489 int32 type
00490 int32 LINK_FRAME=0
00491 int32 HEADER_FRAME=1
00492
00493 # The desired orientation of the robot link specified as a quaternion
00494 geometry_msgs/Quaternion orientation
00495
00496 # optional RPY error tolerances specified if
00497 float64 absolute_roll_tolerance
00498 float64 absolute_pitch_tolerance
00499 float64 absolute_yaw_tolerance
00500
00501 # Constraint weighting factor - a weight for this constraint
00502 float64 weight
00503
00504 ================================================================================
00505 MSG: arm_navigation_msgs/VisibilityConstraint
00506 # This message contains the definition of a visibility constraint.
00507 Header header
00508
00509 # The point stamped target that needs to be kept within view of the sensor
00510 geometry_msgs/PointStamped target
00511
00512 # The local pose of the frame in which visibility is to be maintained
00513 # The frame id should represent the robot link to which the sensor is attached
00514 # The visual axis of the sensor is assumed to be along the X axis of this frame
00515 geometry_msgs/PoseStamped sensor_pose
00516
00517 # The deviation (in radians) that will be tolerated
00518 # Constraint error will be measured as the solid angle between the
00519 # X axis of the frame defined above and the vector between the origin
00520 # of the frame defined above and the target location
00521 float64 absolute_tolerance
00522
00523
00524 ================================================================================
00525 MSG: geometry_msgs/PointStamped
00526 # This represents a Point with reference coordinate frame and timestamp
00527 Header header
00528 Point point
00529
00530 ================================================================================
00531 MSG: arm_navigation_msgs/OrderedCollisionOperations
00532 # A set of collision operations that will be performed in the order they are specified
00533 CollisionOperation[] collision_operations
00534 ================================================================================
00535 MSG: arm_navigation_msgs/CollisionOperation
00536 # A definition of a collision operation
00537 # E.g. ("gripper",COLLISION_SET_ALL,ENABLE) will enable collisions
00538 # between the gripper and all objects in the collision space
00539
00540 string object1
00541 string object2
00542 string COLLISION_SET_ALL="all"
00543 string COLLISION_SET_OBJECTS="objects"
00544 string COLLISION_SET_ATTACHED_OBJECTS="attached"
00545
00546 # The penetration distance to which collisions are allowed. This is 0.0 by default.
00547 float64 penetration_distance
00548
00549 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above
00550 int32 operation
00551 int32 DISABLE=0
00552 int32 ENABLE=1
00553
00554 """
00555 __slots__ = ['header','goal_id','goal']
00556 _slot_types = ['std_msgs/Header','actionlib_msgs/GoalID','arm_navigation_msgs/MoveArmGoal']
00557
00558 def __init__(self, *args, **kwds):
00559 """
00560 Constructor. Any message fields that are implicitly/explicitly
00561 set to None will be assigned a default value. The recommend
00562 use is keyword arguments as this is more robust to future message
00563 changes. You cannot mix in-order arguments and keyword arguments.
00564
00565 The available fields are:
00566 header,goal_id,goal
00567
00568 :param args: complete set of field values, in .msg order
00569 :param kwds: use keyword arguments corresponding to message field names
00570 to set specific fields.
00571 """
00572 if args or kwds:
00573 super(MoveArmActionGoal, self).__init__(*args, **kwds)
00574
00575 if self.header is None:
00576 self.header = std_msgs.msg.Header()
00577 if self.goal_id is None:
00578 self.goal_id = actionlib_msgs.msg.GoalID()
00579 if self.goal is None:
00580 self.goal = arm_navigation_msgs.msg.MoveArmGoal()
00581 else:
00582 self.header = std_msgs.msg.Header()
00583 self.goal_id = actionlib_msgs.msg.GoalID()
00584 self.goal = arm_navigation_msgs.msg.MoveArmGoal()
00585
00586 def _get_types(self):
00587 """
00588 internal API method
00589 """
00590 return self._slot_types
00591
00592 def serialize(self, buff):
00593 """
00594 serialize message into buffer
00595 :param buff: buffer, ``StringIO``
00596 """
00597 try:
00598 _x = self
00599 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00600 _x = self.header.frame_id
00601 length = len(_x)
00602 if python3 or type(_x) == unicode:
00603 _x = _x.encode('utf-8')
00604 length = len(_x)
00605 buff.write(struct.pack('<I%ss'%length, length, _x))
00606 _x = self
00607 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00608 _x = self.goal_id.id
00609 length = len(_x)
00610 if python3 or type(_x) == unicode:
00611 _x = _x.encode('utf-8')
00612 length = len(_x)
00613 buff.write(struct.pack('<I%ss'%length, length, _x))
00614 _x = self.goal.planner_service_name
00615 length = len(_x)
00616 if python3 or type(_x) == unicode:
00617 _x = _x.encode('utf-8')
00618 length = len(_x)
00619 buff.write(struct.pack('<I%ss'%length, length, _x))
00620 _x = self
00621 buff.write(_struct_3I.pack(_x.goal.planning_scene_diff.robot_state.joint_state.header.seq, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs))
00622 _x = self.goal.planning_scene_diff.robot_state.joint_state.header.frame_id
00623 length = len(_x)
00624 if python3 or type(_x) == unicode:
00625 _x = _x.encode('utf-8')
00626 length = len(_x)
00627 buff.write(struct.pack('<I%ss'%length, length, _x))
00628 length = len(self.goal.planning_scene_diff.robot_state.joint_state.name)
00629 buff.write(_struct_I.pack(length))
00630 for val1 in self.goal.planning_scene_diff.robot_state.joint_state.name:
00631 length = len(val1)
00632 if python3 or type(val1) == unicode:
00633 val1 = val1.encode('utf-8')
00634 length = len(val1)
00635 buff.write(struct.pack('<I%ss'%length, length, val1))
00636 length = len(self.goal.planning_scene_diff.robot_state.joint_state.position)
00637 buff.write(_struct_I.pack(length))
00638 pattern = '<%sd'%length
00639 buff.write(struct.pack(pattern, *self.goal.planning_scene_diff.robot_state.joint_state.position))
00640 length = len(self.goal.planning_scene_diff.robot_state.joint_state.velocity)
00641 buff.write(_struct_I.pack(length))
00642 pattern = '<%sd'%length
00643 buff.write(struct.pack(pattern, *self.goal.planning_scene_diff.robot_state.joint_state.velocity))
00644 length = len(self.goal.planning_scene_diff.robot_state.joint_state.effort)
00645 buff.write(_struct_I.pack(length))
00646 pattern = '<%sd'%length
00647 buff.write(struct.pack(pattern, *self.goal.planning_scene_diff.robot_state.joint_state.effort))
00648 _x = self
00649 buff.write(_struct_2I.pack(_x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs))
00650 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names)
00651 buff.write(_struct_I.pack(length))
00652 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names:
00653 length = len(val1)
00654 if python3 or type(val1) == unicode:
00655 val1 = val1.encode('utf-8')
00656 length = len(val1)
00657 buff.write(struct.pack('<I%ss'%length, length, val1))
00658 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids)
00659 buff.write(_struct_I.pack(length))
00660 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids:
00661 length = len(val1)
00662 if python3 or type(val1) == unicode:
00663 val1 = val1.encode('utf-8')
00664 length = len(val1)
00665 buff.write(struct.pack('<I%ss'%length, length, val1))
00666 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids)
00667 buff.write(_struct_I.pack(length))
00668 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids:
00669 length = len(val1)
00670 if python3 or type(val1) == unicode:
00671 val1 = val1.encode('utf-8')
00672 length = len(val1)
00673 buff.write(struct.pack('<I%ss'%length, length, val1))
00674 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses)
00675 buff.write(_struct_I.pack(length))
00676 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses:
00677 _v1 = val1.position
00678 _x = _v1
00679 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00680 _v2 = val1.orientation
00681 _x = _v2
00682 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00683 length = len(self.goal.planning_scene_diff.fixed_frame_transforms)
00684 buff.write(_struct_I.pack(length))
00685 for val1 in self.goal.planning_scene_diff.fixed_frame_transforms:
00686 _v3 = val1.header
00687 buff.write(_struct_I.pack(_v3.seq))
00688 _v4 = _v3.stamp
00689 _x = _v4
00690 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00691 _x = _v3.frame_id
00692 length = len(_x)
00693 if python3 or type(_x) == unicode:
00694 _x = _x.encode('utf-8')
00695 length = len(_x)
00696 buff.write(struct.pack('<I%ss'%length, length, _x))
00697 _x = val1.child_frame_id
00698 length = len(_x)
00699 if python3 or type(_x) == unicode:
00700 _x = _x.encode('utf-8')
00701 length = len(_x)
00702 buff.write(struct.pack('<I%ss'%length, length, _x))
00703 _v5 = val1.transform
00704 _v6 = _v5.translation
00705 _x = _v6
00706 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00707 _v7 = _v5.rotation
00708 _x = _v7
00709 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00710 length = len(self.goal.planning_scene_diff.allowed_collision_matrix.link_names)
00711 buff.write(_struct_I.pack(length))
00712 for val1 in self.goal.planning_scene_diff.allowed_collision_matrix.link_names:
00713 length = len(val1)
00714 if python3 or type(val1) == unicode:
00715 val1 = val1.encode('utf-8')
00716 length = len(val1)
00717 buff.write(struct.pack('<I%ss'%length, length, val1))
00718 length = len(self.goal.planning_scene_diff.allowed_collision_matrix.entries)
00719 buff.write(_struct_I.pack(length))
00720 for val1 in self.goal.planning_scene_diff.allowed_collision_matrix.entries:
00721 length = len(val1.enabled)
00722 buff.write(_struct_I.pack(length))
00723 pattern = '<%sB'%length
00724 buff.write(struct.pack(pattern, *val1.enabled))
00725 length = len(self.goal.planning_scene_diff.allowed_contacts)
00726 buff.write(_struct_I.pack(length))
00727 for val1 in self.goal.planning_scene_diff.allowed_contacts:
00728 _x = val1.name
00729 length = len(_x)
00730 if python3 or type(_x) == unicode:
00731 _x = _x.encode('utf-8')
00732 length = len(_x)
00733 buff.write(struct.pack('<I%ss'%length, length, _x))
00734 _v8 = val1.shape
00735 buff.write(_struct_b.pack(_v8.type))
00736 length = len(_v8.dimensions)
00737 buff.write(_struct_I.pack(length))
00738 pattern = '<%sd'%length
00739 buff.write(struct.pack(pattern, *_v8.dimensions))
00740 length = len(_v8.triangles)
00741 buff.write(_struct_I.pack(length))
00742 pattern = '<%si'%length
00743 buff.write(struct.pack(pattern, *_v8.triangles))
00744 length = len(_v8.vertices)
00745 buff.write(_struct_I.pack(length))
00746 for val3 in _v8.vertices:
00747 _x = val3
00748 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00749 _v9 = val1.pose_stamped
00750 _v10 = _v9.header
00751 buff.write(_struct_I.pack(_v10.seq))
00752 _v11 = _v10.stamp
00753 _x = _v11
00754 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00755 _x = _v10.frame_id
00756 length = len(_x)
00757 if python3 or type(_x) == unicode:
00758 _x = _x.encode('utf-8')
00759 length = len(_x)
00760 buff.write(struct.pack('<I%ss'%length, length, _x))
00761 _v12 = _v9.pose
00762 _v13 = _v12.position
00763 _x = _v13
00764 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00765 _v14 = _v12.orientation
00766 _x = _v14
00767 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00768 length = len(val1.link_names)
00769 buff.write(_struct_I.pack(length))
00770 for val2 in val1.link_names:
00771 length = len(val2)
00772 if python3 or type(val2) == unicode:
00773 val2 = val2.encode('utf-8')
00774 length = len(val2)
00775 buff.write(struct.pack('<I%ss'%length, length, val2))
00776 buff.write(_struct_d.pack(val1.penetration_depth))
00777 length = len(self.goal.planning_scene_diff.link_padding)
00778 buff.write(_struct_I.pack(length))
00779 for val1 in self.goal.planning_scene_diff.link_padding:
00780 _x = val1.link_name
00781 length = len(_x)
00782 if python3 or type(_x) == unicode:
00783 _x = _x.encode('utf-8')
00784 length = len(_x)
00785 buff.write(struct.pack('<I%ss'%length, length, _x))
00786 buff.write(_struct_d.pack(val1.padding))
00787 length = len(self.goal.planning_scene_diff.collision_objects)
00788 buff.write(_struct_I.pack(length))
00789 for val1 in self.goal.planning_scene_diff.collision_objects:
00790 _v15 = val1.header
00791 buff.write(_struct_I.pack(_v15.seq))
00792 _v16 = _v15.stamp
00793 _x = _v16
00794 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00795 _x = _v15.frame_id
00796 length = len(_x)
00797 if python3 or type(_x) == unicode:
00798 _x = _x.encode('utf-8')
00799 length = len(_x)
00800 buff.write(struct.pack('<I%ss'%length, length, _x))
00801 _x = val1.id
00802 length = len(_x)
00803 if python3 or type(_x) == unicode:
00804 _x = _x.encode('utf-8')
00805 length = len(_x)
00806 buff.write(struct.pack('<I%ss'%length, length, _x))
00807 buff.write(_struct_f.pack(val1.padding))
00808 _v17 = val1.operation
00809 buff.write(_struct_b.pack(_v17.operation))
00810 length = len(val1.shapes)
00811 buff.write(_struct_I.pack(length))
00812 for val2 in val1.shapes:
00813 buff.write(_struct_b.pack(val2.type))
00814 length = len(val2.dimensions)
00815 buff.write(_struct_I.pack(length))
00816 pattern = '<%sd'%length
00817 buff.write(struct.pack(pattern, *val2.dimensions))
00818 length = len(val2.triangles)
00819 buff.write(_struct_I.pack(length))
00820 pattern = '<%si'%length
00821 buff.write(struct.pack(pattern, *val2.triangles))
00822 length = len(val2.vertices)
00823 buff.write(_struct_I.pack(length))
00824 for val3 in val2.vertices:
00825 _x = val3
00826 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00827 length = len(val1.poses)
00828 buff.write(_struct_I.pack(length))
00829 for val2 in val1.poses:
00830 _v18 = val2.position
00831 _x = _v18
00832 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00833 _v19 = val2.orientation
00834 _x = _v19
00835 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00836 length = len(self.goal.planning_scene_diff.attached_collision_objects)
00837 buff.write(_struct_I.pack(length))
00838 for val1 in self.goal.planning_scene_diff.attached_collision_objects:
00839 _x = val1.link_name
00840 length = len(_x)
00841 if python3 or type(_x) == unicode:
00842 _x = _x.encode('utf-8')
00843 length = len(_x)
00844 buff.write(struct.pack('<I%ss'%length, length, _x))
00845 _v20 = val1.object
00846 _v21 = _v20.header
00847 buff.write(_struct_I.pack(_v21.seq))
00848 _v22 = _v21.stamp
00849 _x = _v22
00850 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00851 _x = _v21.frame_id
00852 length = len(_x)
00853 if python3 or type(_x) == unicode:
00854 _x = _x.encode('utf-8')
00855 length = len(_x)
00856 buff.write(struct.pack('<I%ss'%length, length, _x))
00857 _x = _v20.id
00858 length = len(_x)
00859 if python3 or type(_x) == unicode:
00860 _x = _x.encode('utf-8')
00861 length = len(_x)
00862 buff.write(struct.pack('<I%ss'%length, length, _x))
00863 buff.write(_struct_f.pack(_v20.padding))
00864 _v23 = _v20.operation
00865 buff.write(_struct_b.pack(_v23.operation))
00866 length = len(_v20.shapes)
00867 buff.write(_struct_I.pack(length))
00868 for val3 in _v20.shapes:
00869 buff.write(_struct_b.pack(val3.type))
00870 length = len(val3.dimensions)
00871 buff.write(_struct_I.pack(length))
00872 pattern = '<%sd'%length
00873 buff.write(struct.pack(pattern, *val3.dimensions))
00874 length = len(val3.triangles)
00875 buff.write(_struct_I.pack(length))
00876 pattern = '<%si'%length
00877 buff.write(struct.pack(pattern, *val3.triangles))
00878 length = len(val3.vertices)
00879 buff.write(_struct_I.pack(length))
00880 for val4 in val3.vertices:
00881 _x = val4
00882 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00883 length = len(_v20.poses)
00884 buff.write(_struct_I.pack(length))
00885 for val3 in _v20.poses:
00886 _v24 = val3.position
00887 _x = _v24
00888 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00889 _v25 = val3.orientation
00890 _x = _v25
00891 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00892 length = len(val1.touch_links)
00893 buff.write(_struct_I.pack(length))
00894 for val2 in val1.touch_links:
00895 length = len(val2)
00896 if python3 or type(val2) == unicode:
00897 val2 = val2.encode('utf-8')
00898 length = len(val2)
00899 buff.write(struct.pack('<I%ss'%length, length, val2))
00900 _x = self
00901 buff.write(_struct_3I.pack(_x.goal.planning_scene_diff.collision_map.header.seq, _x.goal.planning_scene_diff.collision_map.header.stamp.secs, _x.goal.planning_scene_diff.collision_map.header.stamp.nsecs))
00902 _x = self.goal.planning_scene_diff.collision_map.header.frame_id
00903 length = len(_x)
00904 if python3 or type(_x) == unicode:
00905 _x = _x.encode('utf-8')
00906 length = len(_x)
00907 buff.write(struct.pack('<I%ss'%length, length, _x))
00908 length = len(self.goal.planning_scene_diff.collision_map.boxes)
00909 buff.write(_struct_I.pack(length))
00910 for val1 in self.goal.planning_scene_diff.collision_map.boxes:
00911 _v26 = val1.center
00912 _x = _v26
00913 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00914 _v27 = val1.extents
00915 _x = _v27
00916 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00917 _v28 = val1.axis
00918 _x = _v28
00919 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00920 buff.write(_struct_f.pack(val1.angle))
00921 buff.write(_struct_b.pack(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.type))
00922 length = len(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions)
00923 buff.write(_struct_I.pack(length))
00924 pattern = '<%sd'%length
00925 buff.write(struct.pack(pattern, *self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions))
00926 length = len(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.triangles)
00927 buff.write(_struct_I.pack(length))
00928 pattern = '<%si'%length
00929 buff.write(struct.pack(pattern, *self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.triangles))
00930 length = len(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices)
00931 buff.write(_struct_I.pack(length))
00932 for val1 in self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices:
00933 _x = val1
00934 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00935 _x = self
00936 buff.write(_struct_3I.pack(_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
00937 _x = self.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id
00938 length = len(_x)
00939 if python3 or type(_x) == unicode:
00940 _x = _x.encode('utf-8')
00941 length = len(_x)
00942 buff.write(struct.pack('<I%ss'%length, length, _x))
00943 _x = self
00944 buff.write(_struct_7d3I.pack(_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.goal.motion_plan_request.start_state.joint_state.header.seq, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.nsecs))
00945 _x = self.goal.motion_plan_request.start_state.joint_state.header.frame_id
00946 length = len(_x)
00947 if python3 or type(_x) == unicode:
00948 _x = _x.encode('utf-8')
00949 length = len(_x)
00950 buff.write(struct.pack('<I%ss'%length, length, _x))
00951 length = len(self.goal.motion_plan_request.start_state.joint_state.name)
00952 buff.write(_struct_I.pack(length))
00953 for val1 in self.goal.motion_plan_request.start_state.joint_state.name:
00954 length = len(val1)
00955 if python3 or type(val1) == unicode:
00956 val1 = val1.encode('utf-8')
00957 length = len(val1)
00958 buff.write(struct.pack('<I%ss'%length, length, val1))
00959 length = len(self.goal.motion_plan_request.start_state.joint_state.position)
00960 buff.write(_struct_I.pack(length))
00961 pattern = '<%sd'%length
00962 buff.write(struct.pack(pattern, *self.goal.motion_plan_request.start_state.joint_state.position))
00963 length = len(self.goal.motion_plan_request.start_state.joint_state.velocity)
00964 buff.write(_struct_I.pack(length))
00965 pattern = '<%sd'%length
00966 buff.write(struct.pack(pattern, *self.goal.motion_plan_request.start_state.joint_state.velocity))
00967 length = len(self.goal.motion_plan_request.start_state.joint_state.effort)
00968 buff.write(_struct_I.pack(length))
00969 pattern = '<%sd'%length
00970 buff.write(struct.pack(pattern, *self.goal.motion_plan_request.start_state.joint_state.effort))
00971 _x = self
00972 buff.write(_struct_2I.pack(_x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs))
00973 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names)
00974 buff.write(_struct_I.pack(length))
00975 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names:
00976 length = len(val1)
00977 if python3 or type(val1) == unicode:
00978 val1 = val1.encode('utf-8')
00979 length = len(val1)
00980 buff.write(struct.pack('<I%ss'%length, length, val1))
00981 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids)
00982 buff.write(_struct_I.pack(length))
00983 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids:
00984 length = len(val1)
00985 if python3 or type(val1) == unicode:
00986 val1 = val1.encode('utf-8')
00987 length = len(val1)
00988 buff.write(struct.pack('<I%ss'%length, length, val1))
00989 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids)
00990 buff.write(_struct_I.pack(length))
00991 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids:
00992 length = len(val1)
00993 if python3 or type(val1) == unicode:
00994 val1 = val1.encode('utf-8')
00995 length = len(val1)
00996 buff.write(struct.pack('<I%ss'%length, length, val1))
00997 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses)
00998 buff.write(_struct_I.pack(length))
00999 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses:
01000 _v29 = val1.position
01001 _x = _v29
01002 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01003 _v30 = val1.orientation
01004 _x = _v30
01005 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01006 length = len(self.goal.motion_plan_request.goal_constraints.joint_constraints)
01007 buff.write(_struct_I.pack(length))
01008 for val1 in self.goal.motion_plan_request.goal_constraints.joint_constraints:
01009 _x = val1.joint_name
01010 length = len(_x)
01011 if python3 or type(_x) == unicode:
01012 _x = _x.encode('utf-8')
01013 length = len(_x)
01014 buff.write(struct.pack('<I%ss'%length, length, _x))
01015 _x = val1
01016 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01017 length = len(self.goal.motion_plan_request.goal_constraints.position_constraints)
01018 buff.write(_struct_I.pack(length))
01019 for val1 in self.goal.motion_plan_request.goal_constraints.position_constraints:
01020 _v31 = val1.header
01021 buff.write(_struct_I.pack(_v31.seq))
01022 _v32 = _v31.stamp
01023 _x = _v32
01024 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01025 _x = _v31.frame_id
01026 length = len(_x)
01027 if python3 or type(_x) == unicode:
01028 _x = _x.encode('utf-8')
01029 length = len(_x)
01030 buff.write(struct.pack('<I%ss'%length, length, _x))
01031 _x = val1.link_name
01032 length = len(_x)
01033 if python3 or type(_x) == unicode:
01034 _x = _x.encode('utf-8')
01035 length = len(_x)
01036 buff.write(struct.pack('<I%ss'%length, length, _x))
01037 _v33 = val1.target_point_offset
01038 _x = _v33
01039 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01040 _v34 = val1.position
01041 _x = _v34
01042 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01043 _v35 = val1.constraint_region_shape
01044 buff.write(_struct_b.pack(_v35.type))
01045 length = len(_v35.dimensions)
01046 buff.write(_struct_I.pack(length))
01047 pattern = '<%sd'%length
01048 buff.write(struct.pack(pattern, *_v35.dimensions))
01049 length = len(_v35.triangles)
01050 buff.write(_struct_I.pack(length))
01051 pattern = '<%si'%length
01052 buff.write(struct.pack(pattern, *_v35.triangles))
01053 length = len(_v35.vertices)
01054 buff.write(_struct_I.pack(length))
01055 for val3 in _v35.vertices:
01056 _x = val3
01057 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01058 _v36 = val1.constraint_region_orientation
01059 _x = _v36
01060 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01061 buff.write(_struct_d.pack(val1.weight))
01062 length = len(self.goal.motion_plan_request.goal_constraints.orientation_constraints)
01063 buff.write(_struct_I.pack(length))
01064 for val1 in self.goal.motion_plan_request.goal_constraints.orientation_constraints:
01065 _v37 = val1.header
01066 buff.write(_struct_I.pack(_v37.seq))
01067 _v38 = _v37.stamp
01068 _x = _v38
01069 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01070 _x = _v37.frame_id
01071 length = len(_x)
01072 if python3 or type(_x) == unicode:
01073 _x = _x.encode('utf-8')
01074 length = len(_x)
01075 buff.write(struct.pack('<I%ss'%length, length, _x))
01076 _x = val1.link_name
01077 length = len(_x)
01078 if python3 or type(_x) == unicode:
01079 _x = _x.encode('utf-8')
01080 length = len(_x)
01081 buff.write(struct.pack('<I%ss'%length, length, _x))
01082 buff.write(_struct_i.pack(val1.type))
01083 _v39 = val1.orientation
01084 _x = _v39
01085 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01086 _x = val1
01087 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01088 length = len(self.goal.motion_plan_request.goal_constraints.visibility_constraints)
01089 buff.write(_struct_I.pack(length))
01090 for val1 in self.goal.motion_plan_request.goal_constraints.visibility_constraints:
01091 _v40 = val1.header
01092 buff.write(_struct_I.pack(_v40.seq))
01093 _v41 = _v40.stamp
01094 _x = _v41
01095 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01096 _x = _v40.frame_id
01097 length = len(_x)
01098 if python3 or type(_x) == unicode:
01099 _x = _x.encode('utf-8')
01100 length = len(_x)
01101 buff.write(struct.pack('<I%ss'%length, length, _x))
01102 _v42 = val1.target
01103 _v43 = _v42.header
01104 buff.write(_struct_I.pack(_v43.seq))
01105 _v44 = _v43.stamp
01106 _x = _v44
01107 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01108 _x = _v43.frame_id
01109 length = len(_x)
01110 if python3 or type(_x) == unicode:
01111 _x = _x.encode('utf-8')
01112 length = len(_x)
01113 buff.write(struct.pack('<I%ss'%length, length, _x))
01114 _v45 = _v42.point
01115 _x = _v45
01116 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01117 _v46 = val1.sensor_pose
01118 _v47 = _v46.header
01119 buff.write(_struct_I.pack(_v47.seq))
01120 _v48 = _v47.stamp
01121 _x = _v48
01122 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01123 _x = _v47.frame_id
01124 length = len(_x)
01125 if python3 or type(_x) == unicode:
01126 _x = _x.encode('utf-8')
01127 length = len(_x)
01128 buff.write(struct.pack('<I%ss'%length, length, _x))
01129 _v49 = _v46.pose
01130 _v50 = _v49.position
01131 _x = _v50
01132 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01133 _v51 = _v49.orientation
01134 _x = _v51
01135 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01136 buff.write(_struct_d.pack(val1.absolute_tolerance))
01137 length = len(self.goal.motion_plan_request.path_constraints.joint_constraints)
01138 buff.write(_struct_I.pack(length))
01139 for val1 in self.goal.motion_plan_request.path_constraints.joint_constraints:
01140 _x = val1.joint_name
01141 length = len(_x)
01142 if python3 or type(_x) == unicode:
01143 _x = _x.encode('utf-8')
01144 length = len(_x)
01145 buff.write(struct.pack('<I%ss'%length, length, _x))
01146 _x = val1
01147 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01148 length = len(self.goal.motion_plan_request.path_constraints.position_constraints)
01149 buff.write(_struct_I.pack(length))
01150 for val1 in self.goal.motion_plan_request.path_constraints.position_constraints:
01151 _v52 = val1.header
01152 buff.write(_struct_I.pack(_v52.seq))
01153 _v53 = _v52.stamp
01154 _x = _v53
01155 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01156 _x = _v52.frame_id
01157 length = len(_x)
01158 if python3 or type(_x) == unicode:
01159 _x = _x.encode('utf-8')
01160 length = len(_x)
01161 buff.write(struct.pack('<I%ss'%length, length, _x))
01162 _x = val1.link_name
01163 length = len(_x)
01164 if python3 or type(_x) == unicode:
01165 _x = _x.encode('utf-8')
01166 length = len(_x)
01167 buff.write(struct.pack('<I%ss'%length, length, _x))
01168 _v54 = val1.target_point_offset
01169 _x = _v54
01170 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01171 _v55 = val1.position
01172 _x = _v55
01173 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01174 _v56 = val1.constraint_region_shape
01175 buff.write(_struct_b.pack(_v56.type))
01176 length = len(_v56.dimensions)
01177 buff.write(_struct_I.pack(length))
01178 pattern = '<%sd'%length
01179 buff.write(struct.pack(pattern, *_v56.dimensions))
01180 length = len(_v56.triangles)
01181 buff.write(_struct_I.pack(length))
01182 pattern = '<%si'%length
01183 buff.write(struct.pack(pattern, *_v56.triangles))
01184 length = len(_v56.vertices)
01185 buff.write(_struct_I.pack(length))
01186 for val3 in _v56.vertices:
01187 _x = val3
01188 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01189 _v57 = val1.constraint_region_orientation
01190 _x = _v57
01191 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01192 buff.write(_struct_d.pack(val1.weight))
01193 length = len(self.goal.motion_plan_request.path_constraints.orientation_constraints)
01194 buff.write(_struct_I.pack(length))
01195 for val1 in self.goal.motion_plan_request.path_constraints.orientation_constraints:
01196 _v58 = val1.header
01197 buff.write(_struct_I.pack(_v58.seq))
01198 _v59 = _v58.stamp
01199 _x = _v59
01200 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01201 _x = _v58.frame_id
01202 length = len(_x)
01203 if python3 or type(_x) == unicode:
01204 _x = _x.encode('utf-8')
01205 length = len(_x)
01206 buff.write(struct.pack('<I%ss'%length, length, _x))
01207 _x = val1.link_name
01208 length = len(_x)
01209 if python3 or type(_x) == unicode:
01210 _x = _x.encode('utf-8')
01211 length = len(_x)
01212 buff.write(struct.pack('<I%ss'%length, length, _x))
01213 buff.write(_struct_i.pack(val1.type))
01214 _v60 = val1.orientation
01215 _x = _v60
01216 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01217 _x = val1
01218 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01219 length = len(self.goal.motion_plan_request.path_constraints.visibility_constraints)
01220 buff.write(_struct_I.pack(length))
01221 for val1 in self.goal.motion_plan_request.path_constraints.visibility_constraints:
01222 _v61 = val1.header
01223 buff.write(_struct_I.pack(_v61.seq))
01224 _v62 = _v61.stamp
01225 _x = _v62
01226 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01227 _x = _v61.frame_id
01228 length = len(_x)
01229 if python3 or type(_x) == unicode:
01230 _x = _x.encode('utf-8')
01231 length = len(_x)
01232 buff.write(struct.pack('<I%ss'%length, length, _x))
01233 _v63 = val1.target
01234 _v64 = _v63.header
01235 buff.write(_struct_I.pack(_v64.seq))
01236 _v65 = _v64.stamp
01237 _x = _v65
01238 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01239 _x = _v64.frame_id
01240 length = len(_x)
01241 if python3 or type(_x) == unicode:
01242 _x = _x.encode('utf-8')
01243 length = len(_x)
01244 buff.write(struct.pack('<I%ss'%length, length, _x))
01245 _v66 = _v63.point
01246 _x = _v66
01247 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01248 _v67 = val1.sensor_pose
01249 _v68 = _v67.header
01250 buff.write(_struct_I.pack(_v68.seq))
01251 _v69 = _v68.stamp
01252 _x = _v69
01253 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01254 _x = _v68.frame_id
01255 length = len(_x)
01256 if python3 or type(_x) == unicode:
01257 _x = _x.encode('utf-8')
01258 length = len(_x)
01259 buff.write(struct.pack('<I%ss'%length, length, _x))
01260 _v70 = _v67.pose
01261 _v71 = _v70.position
01262 _x = _v71
01263 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01264 _v72 = _v70.orientation
01265 _x = _v72
01266 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01267 buff.write(_struct_d.pack(val1.absolute_tolerance))
01268 _x = self.goal.motion_plan_request.planner_id
01269 length = len(_x)
01270 if python3 or type(_x) == unicode:
01271 _x = _x.encode('utf-8')
01272 length = len(_x)
01273 buff.write(struct.pack('<I%ss'%length, length, _x))
01274 _x = self.goal.motion_plan_request.group_name
01275 length = len(_x)
01276 if python3 or type(_x) == unicode:
01277 _x = _x.encode('utf-8')
01278 length = len(_x)
01279 buff.write(struct.pack('<I%ss'%length, length, _x))
01280 _x = self
01281 buff.write(_struct_7i.pack(_x.goal.motion_plan_request.num_planning_attempts, _x.goal.motion_plan_request.allowed_planning_time.secs, _x.goal.motion_plan_request.allowed_planning_time.nsecs, _x.goal.motion_plan_request.expected_path_duration.secs, _x.goal.motion_plan_request.expected_path_duration.nsecs, _x.goal.motion_plan_request.expected_path_dt.secs, _x.goal.motion_plan_request.expected_path_dt.nsecs))
01282 length = len(self.goal.operations.collision_operations)
01283 buff.write(_struct_I.pack(length))
01284 for val1 in self.goal.operations.collision_operations:
01285 _x = val1.object1
01286 length = len(_x)
01287 if python3 or type(_x) == unicode:
01288 _x = _x.encode('utf-8')
01289 length = len(_x)
01290 buff.write(struct.pack('<I%ss'%length, length, _x))
01291 _x = val1.object2
01292 length = len(_x)
01293 if python3 or type(_x) == unicode:
01294 _x = _x.encode('utf-8')
01295 length = len(_x)
01296 buff.write(struct.pack('<I%ss'%length, length, _x))
01297 _x = val1
01298 buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
01299 _x = self
01300 buff.write(_struct_4B.pack(_x.goal.accept_partial_plans, _x.goal.accept_invalid_goals, _x.goal.disable_ik, _x.goal.disable_collision_monitoring))
01301 except struct.error as se: self._check_types(se)
01302 except TypeError as te: self._check_types(te)
01303
01304 def deserialize(self, str):
01305 """
01306 unpack serialized message in str into this message instance
01307 :param str: byte array of serialized message, ``str``
01308 """
01309 try:
01310 if self.header is None:
01311 self.header = std_msgs.msg.Header()
01312 if self.goal_id is None:
01313 self.goal_id = actionlib_msgs.msg.GoalID()
01314 if self.goal is None:
01315 self.goal = arm_navigation_msgs.msg.MoveArmGoal()
01316 end = 0
01317 _x = self
01318 start = end
01319 end += 12
01320 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01321 start = end
01322 end += 4
01323 (length,) = _struct_I.unpack(str[start:end])
01324 start = end
01325 end += length
01326 if python3:
01327 self.header.frame_id = str[start:end].decode('utf-8')
01328 else:
01329 self.header.frame_id = str[start:end]
01330 _x = self
01331 start = end
01332 end += 8
01333 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01334 start = end
01335 end += 4
01336 (length,) = _struct_I.unpack(str[start:end])
01337 start = end
01338 end += length
01339 if python3:
01340 self.goal_id.id = str[start:end].decode('utf-8')
01341 else:
01342 self.goal_id.id = str[start:end]
01343 start = end
01344 end += 4
01345 (length,) = _struct_I.unpack(str[start:end])
01346 start = end
01347 end += length
01348 if python3:
01349 self.goal.planner_service_name = str[start:end].decode('utf-8')
01350 else:
01351 self.goal.planner_service_name = str[start:end]
01352 _x = self
01353 start = end
01354 end += 12
01355 (_x.goal.planning_scene_diff.robot_state.joint_state.header.seq, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01356 start = end
01357 end += 4
01358 (length,) = _struct_I.unpack(str[start:end])
01359 start = end
01360 end += length
01361 if python3:
01362 self.goal.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
01363 else:
01364 self.goal.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end]
01365 start = end
01366 end += 4
01367 (length,) = _struct_I.unpack(str[start:end])
01368 self.goal.planning_scene_diff.robot_state.joint_state.name = []
01369 for i in range(0, length):
01370 start = end
01371 end += 4
01372 (length,) = _struct_I.unpack(str[start:end])
01373 start = end
01374 end += length
01375 if python3:
01376 val1 = str[start:end].decode('utf-8')
01377 else:
01378 val1 = str[start:end]
01379 self.goal.planning_scene_diff.robot_state.joint_state.name.append(val1)
01380 start = end
01381 end += 4
01382 (length,) = _struct_I.unpack(str[start:end])
01383 pattern = '<%sd'%length
01384 start = end
01385 end += struct.calcsize(pattern)
01386 self.goal.planning_scene_diff.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
01387 start = end
01388 end += 4
01389 (length,) = _struct_I.unpack(str[start:end])
01390 pattern = '<%sd'%length
01391 start = end
01392 end += struct.calcsize(pattern)
01393 self.goal.planning_scene_diff.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
01394 start = end
01395 end += 4
01396 (length,) = _struct_I.unpack(str[start:end])
01397 pattern = '<%sd'%length
01398 start = end
01399 end += struct.calcsize(pattern)
01400 self.goal.planning_scene_diff.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
01401 _x = self
01402 start = end
01403 end += 8
01404 (_x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01405 start = end
01406 end += 4
01407 (length,) = _struct_I.unpack(str[start:end])
01408 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names = []
01409 for i in range(0, length):
01410 start = end
01411 end += 4
01412 (length,) = _struct_I.unpack(str[start:end])
01413 start = end
01414 end += length
01415 if python3:
01416 val1 = str[start:end].decode('utf-8')
01417 else:
01418 val1 = str[start:end]
01419 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names.append(val1)
01420 start = end
01421 end += 4
01422 (length,) = _struct_I.unpack(str[start:end])
01423 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids = []
01424 for i in range(0, length):
01425 start = end
01426 end += 4
01427 (length,) = _struct_I.unpack(str[start:end])
01428 start = end
01429 end += length
01430 if python3:
01431 val1 = str[start:end].decode('utf-8')
01432 else:
01433 val1 = str[start:end]
01434 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids.append(val1)
01435 start = end
01436 end += 4
01437 (length,) = _struct_I.unpack(str[start:end])
01438 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids = []
01439 for i in range(0, length):
01440 start = end
01441 end += 4
01442 (length,) = _struct_I.unpack(str[start:end])
01443 start = end
01444 end += length
01445 if python3:
01446 val1 = str[start:end].decode('utf-8')
01447 else:
01448 val1 = str[start:end]
01449 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
01450 start = end
01451 end += 4
01452 (length,) = _struct_I.unpack(str[start:end])
01453 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses = []
01454 for i in range(0, length):
01455 val1 = geometry_msgs.msg.Pose()
01456 _v73 = val1.position
01457 _x = _v73
01458 start = end
01459 end += 24
01460 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01461 _v74 = val1.orientation
01462 _x = _v74
01463 start = end
01464 end += 32
01465 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01466 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses.append(val1)
01467 start = end
01468 end += 4
01469 (length,) = _struct_I.unpack(str[start:end])
01470 self.goal.planning_scene_diff.fixed_frame_transforms = []
01471 for i in range(0, length):
01472 val1 = geometry_msgs.msg.TransformStamped()
01473 _v75 = val1.header
01474 start = end
01475 end += 4
01476 (_v75.seq,) = _struct_I.unpack(str[start:end])
01477 _v76 = _v75.stamp
01478 _x = _v76
01479 start = end
01480 end += 8
01481 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01482 start = end
01483 end += 4
01484 (length,) = _struct_I.unpack(str[start:end])
01485 start = end
01486 end += length
01487 if python3:
01488 _v75.frame_id = str[start:end].decode('utf-8')
01489 else:
01490 _v75.frame_id = str[start:end]
01491 start = end
01492 end += 4
01493 (length,) = _struct_I.unpack(str[start:end])
01494 start = end
01495 end += length
01496 if python3:
01497 val1.child_frame_id = str[start:end].decode('utf-8')
01498 else:
01499 val1.child_frame_id = str[start:end]
01500 _v77 = val1.transform
01501 _v78 = _v77.translation
01502 _x = _v78
01503 start = end
01504 end += 24
01505 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01506 _v79 = _v77.rotation
01507 _x = _v79
01508 start = end
01509 end += 32
01510 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01511 self.goal.planning_scene_diff.fixed_frame_transforms.append(val1)
01512 start = end
01513 end += 4
01514 (length,) = _struct_I.unpack(str[start:end])
01515 self.goal.planning_scene_diff.allowed_collision_matrix.link_names = []
01516 for i in range(0, length):
01517 start = end
01518 end += 4
01519 (length,) = _struct_I.unpack(str[start:end])
01520 start = end
01521 end += length
01522 if python3:
01523 val1 = str[start:end].decode('utf-8')
01524 else:
01525 val1 = str[start:end]
01526 self.goal.planning_scene_diff.allowed_collision_matrix.link_names.append(val1)
01527 start = end
01528 end += 4
01529 (length,) = _struct_I.unpack(str[start:end])
01530 self.goal.planning_scene_diff.allowed_collision_matrix.entries = []
01531 for i in range(0, length):
01532 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
01533 start = end
01534 end += 4
01535 (length,) = _struct_I.unpack(str[start:end])
01536 pattern = '<%sB'%length
01537 start = end
01538 end += struct.calcsize(pattern)
01539 val1.enabled = struct.unpack(pattern, str[start:end])
01540 val1.enabled = map(bool, val1.enabled)
01541 self.goal.planning_scene_diff.allowed_collision_matrix.entries.append(val1)
01542 start = end
01543 end += 4
01544 (length,) = _struct_I.unpack(str[start:end])
01545 self.goal.planning_scene_diff.allowed_contacts = []
01546 for i in range(0, length):
01547 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
01548 start = end
01549 end += 4
01550 (length,) = _struct_I.unpack(str[start:end])
01551 start = end
01552 end += length
01553 if python3:
01554 val1.name = str[start:end].decode('utf-8')
01555 else:
01556 val1.name = str[start:end]
01557 _v80 = val1.shape
01558 start = end
01559 end += 1
01560 (_v80.type,) = _struct_b.unpack(str[start:end])
01561 start = end
01562 end += 4
01563 (length,) = _struct_I.unpack(str[start:end])
01564 pattern = '<%sd'%length
01565 start = end
01566 end += struct.calcsize(pattern)
01567 _v80.dimensions = struct.unpack(pattern, str[start:end])
01568 start = end
01569 end += 4
01570 (length,) = _struct_I.unpack(str[start:end])
01571 pattern = '<%si'%length
01572 start = end
01573 end += struct.calcsize(pattern)
01574 _v80.triangles = struct.unpack(pattern, str[start:end])
01575 start = end
01576 end += 4
01577 (length,) = _struct_I.unpack(str[start:end])
01578 _v80.vertices = []
01579 for i in range(0, length):
01580 val3 = geometry_msgs.msg.Point()
01581 _x = val3
01582 start = end
01583 end += 24
01584 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01585 _v80.vertices.append(val3)
01586 _v81 = val1.pose_stamped
01587 _v82 = _v81.header
01588 start = end
01589 end += 4
01590 (_v82.seq,) = _struct_I.unpack(str[start:end])
01591 _v83 = _v82.stamp
01592 _x = _v83
01593 start = end
01594 end += 8
01595 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01596 start = end
01597 end += 4
01598 (length,) = _struct_I.unpack(str[start:end])
01599 start = end
01600 end += length
01601 if python3:
01602 _v82.frame_id = str[start:end].decode('utf-8')
01603 else:
01604 _v82.frame_id = str[start:end]
01605 _v84 = _v81.pose
01606 _v85 = _v84.position
01607 _x = _v85
01608 start = end
01609 end += 24
01610 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01611 _v86 = _v84.orientation
01612 _x = _v86
01613 start = end
01614 end += 32
01615 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01616 start = end
01617 end += 4
01618 (length,) = _struct_I.unpack(str[start:end])
01619 val1.link_names = []
01620 for i in range(0, length):
01621 start = end
01622 end += 4
01623 (length,) = _struct_I.unpack(str[start:end])
01624 start = end
01625 end += length
01626 if python3:
01627 val2 = str[start:end].decode('utf-8')
01628 else:
01629 val2 = str[start:end]
01630 val1.link_names.append(val2)
01631 start = end
01632 end += 8
01633 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
01634 self.goal.planning_scene_diff.allowed_contacts.append(val1)
01635 start = end
01636 end += 4
01637 (length,) = _struct_I.unpack(str[start:end])
01638 self.goal.planning_scene_diff.link_padding = []
01639 for i in range(0, length):
01640 val1 = arm_navigation_msgs.msg.LinkPadding()
01641 start = end
01642 end += 4
01643 (length,) = _struct_I.unpack(str[start:end])
01644 start = end
01645 end += length
01646 if python3:
01647 val1.link_name = str[start:end].decode('utf-8')
01648 else:
01649 val1.link_name = str[start:end]
01650 start = end
01651 end += 8
01652 (val1.padding,) = _struct_d.unpack(str[start:end])
01653 self.goal.planning_scene_diff.link_padding.append(val1)
01654 start = end
01655 end += 4
01656 (length,) = _struct_I.unpack(str[start:end])
01657 self.goal.planning_scene_diff.collision_objects = []
01658 for i in range(0, length):
01659 val1 = arm_navigation_msgs.msg.CollisionObject()
01660 _v87 = val1.header
01661 start = end
01662 end += 4
01663 (_v87.seq,) = _struct_I.unpack(str[start:end])
01664 _v88 = _v87.stamp
01665 _x = _v88
01666 start = end
01667 end += 8
01668 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01669 start = end
01670 end += 4
01671 (length,) = _struct_I.unpack(str[start:end])
01672 start = end
01673 end += length
01674 if python3:
01675 _v87.frame_id = str[start:end].decode('utf-8')
01676 else:
01677 _v87.frame_id = str[start:end]
01678 start = end
01679 end += 4
01680 (length,) = _struct_I.unpack(str[start:end])
01681 start = end
01682 end += length
01683 if python3:
01684 val1.id = str[start:end].decode('utf-8')
01685 else:
01686 val1.id = str[start:end]
01687 start = end
01688 end += 4
01689 (val1.padding,) = _struct_f.unpack(str[start:end])
01690 _v89 = val1.operation
01691 start = end
01692 end += 1
01693 (_v89.operation,) = _struct_b.unpack(str[start:end])
01694 start = end
01695 end += 4
01696 (length,) = _struct_I.unpack(str[start:end])
01697 val1.shapes = []
01698 for i in range(0, length):
01699 val2 = arm_navigation_msgs.msg.Shape()
01700 start = end
01701 end += 1
01702 (val2.type,) = _struct_b.unpack(str[start:end])
01703 start = end
01704 end += 4
01705 (length,) = _struct_I.unpack(str[start:end])
01706 pattern = '<%sd'%length
01707 start = end
01708 end += struct.calcsize(pattern)
01709 val2.dimensions = struct.unpack(pattern, str[start:end])
01710 start = end
01711 end += 4
01712 (length,) = _struct_I.unpack(str[start:end])
01713 pattern = '<%si'%length
01714 start = end
01715 end += struct.calcsize(pattern)
01716 val2.triangles = struct.unpack(pattern, str[start:end])
01717 start = end
01718 end += 4
01719 (length,) = _struct_I.unpack(str[start:end])
01720 val2.vertices = []
01721 for i in range(0, length):
01722 val3 = geometry_msgs.msg.Point()
01723 _x = val3
01724 start = end
01725 end += 24
01726 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01727 val2.vertices.append(val3)
01728 val1.shapes.append(val2)
01729 start = end
01730 end += 4
01731 (length,) = _struct_I.unpack(str[start:end])
01732 val1.poses = []
01733 for i in range(0, length):
01734 val2 = geometry_msgs.msg.Pose()
01735 _v90 = val2.position
01736 _x = _v90
01737 start = end
01738 end += 24
01739 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01740 _v91 = val2.orientation
01741 _x = _v91
01742 start = end
01743 end += 32
01744 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01745 val1.poses.append(val2)
01746 self.goal.planning_scene_diff.collision_objects.append(val1)
01747 start = end
01748 end += 4
01749 (length,) = _struct_I.unpack(str[start:end])
01750 self.goal.planning_scene_diff.attached_collision_objects = []
01751 for i in range(0, length):
01752 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
01753 start = end
01754 end += 4
01755 (length,) = _struct_I.unpack(str[start:end])
01756 start = end
01757 end += length
01758 if python3:
01759 val1.link_name = str[start:end].decode('utf-8')
01760 else:
01761 val1.link_name = str[start:end]
01762 _v92 = val1.object
01763 _v93 = _v92.header
01764 start = end
01765 end += 4
01766 (_v93.seq,) = _struct_I.unpack(str[start:end])
01767 _v94 = _v93.stamp
01768 _x = _v94
01769 start = end
01770 end += 8
01771 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01772 start = end
01773 end += 4
01774 (length,) = _struct_I.unpack(str[start:end])
01775 start = end
01776 end += length
01777 if python3:
01778 _v93.frame_id = str[start:end].decode('utf-8')
01779 else:
01780 _v93.frame_id = str[start:end]
01781 start = end
01782 end += 4
01783 (length,) = _struct_I.unpack(str[start:end])
01784 start = end
01785 end += length
01786 if python3:
01787 _v92.id = str[start:end].decode('utf-8')
01788 else:
01789 _v92.id = str[start:end]
01790 start = end
01791 end += 4
01792 (_v92.padding,) = _struct_f.unpack(str[start:end])
01793 _v95 = _v92.operation
01794 start = end
01795 end += 1
01796 (_v95.operation,) = _struct_b.unpack(str[start:end])
01797 start = end
01798 end += 4
01799 (length,) = _struct_I.unpack(str[start:end])
01800 _v92.shapes = []
01801 for i in range(0, length):
01802 val3 = arm_navigation_msgs.msg.Shape()
01803 start = end
01804 end += 1
01805 (val3.type,) = _struct_b.unpack(str[start:end])
01806 start = end
01807 end += 4
01808 (length,) = _struct_I.unpack(str[start:end])
01809 pattern = '<%sd'%length
01810 start = end
01811 end += struct.calcsize(pattern)
01812 val3.dimensions = struct.unpack(pattern, str[start:end])
01813 start = end
01814 end += 4
01815 (length,) = _struct_I.unpack(str[start:end])
01816 pattern = '<%si'%length
01817 start = end
01818 end += struct.calcsize(pattern)
01819 val3.triangles = struct.unpack(pattern, str[start:end])
01820 start = end
01821 end += 4
01822 (length,) = _struct_I.unpack(str[start:end])
01823 val3.vertices = []
01824 for i in range(0, length):
01825 val4 = geometry_msgs.msg.Point()
01826 _x = val4
01827 start = end
01828 end += 24
01829 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01830 val3.vertices.append(val4)
01831 _v92.shapes.append(val3)
01832 start = end
01833 end += 4
01834 (length,) = _struct_I.unpack(str[start:end])
01835 _v92.poses = []
01836 for i in range(0, length):
01837 val3 = geometry_msgs.msg.Pose()
01838 _v96 = val3.position
01839 _x = _v96
01840 start = end
01841 end += 24
01842 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01843 _v97 = val3.orientation
01844 _x = _v97
01845 start = end
01846 end += 32
01847 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01848 _v92.poses.append(val3)
01849 start = end
01850 end += 4
01851 (length,) = _struct_I.unpack(str[start:end])
01852 val1.touch_links = []
01853 for i in range(0, length):
01854 start = end
01855 end += 4
01856 (length,) = _struct_I.unpack(str[start:end])
01857 start = end
01858 end += length
01859 if python3:
01860 val2 = str[start:end].decode('utf-8')
01861 else:
01862 val2 = str[start:end]
01863 val1.touch_links.append(val2)
01864 self.goal.planning_scene_diff.attached_collision_objects.append(val1)
01865 _x = self
01866 start = end
01867 end += 12
01868 (_x.goal.planning_scene_diff.collision_map.header.seq, _x.goal.planning_scene_diff.collision_map.header.stamp.secs, _x.goal.planning_scene_diff.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01869 start = end
01870 end += 4
01871 (length,) = _struct_I.unpack(str[start:end])
01872 start = end
01873 end += length
01874 if python3:
01875 self.goal.planning_scene_diff.collision_map.header.frame_id = str[start:end].decode('utf-8')
01876 else:
01877 self.goal.planning_scene_diff.collision_map.header.frame_id = str[start:end]
01878 start = end
01879 end += 4
01880 (length,) = _struct_I.unpack(str[start:end])
01881 self.goal.planning_scene_diff.collision_map.boxes = []
01882 for i in range(0, length):
01883 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
01884 _v98 = val1.center
01885 _x = _v98
01886 start = end
01887 end += 12
01888 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01889 _v99 = val1.extents
01890 _x = _v99
01891 start = end
01892 end += 12
01893 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01894 _v100 = val1.axis
01895 _x = _v100
01896 start = end
01897 end += 12
01898 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01899 start = end
01900 end += 4
01901 (val1.angle,) = _struct_f.unpack(str[start:end])
01902 self.goal.planning_scene_diff.collision_map.boxes.append(val1)
01903 start = end
01904 end += 1
01905 (self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.type,) = _struct_b.unpack(str[start:end])
01906 start = end
01907 end += 4
01908 (length,) = _struct_I.unpack(str[start:end])
01909 pattern = '<%sd'%length
01910 start = end
01911 end += struct.calcsize(pattern)
01912 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions = struct.unpack(pattern, str[start:end])
01913 start = end
01914 end += 4
01915 (length,) = _struct_I.unpack(str[start:end])
01916 pattern = '<%si'%length
01917 start = end
01918 end += struct.calcsize(pattern)
01919 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.triangles = struct.unpack(pattern, str[start:end])
01920 start = end
01921 end += 4
01922 (length,) = _struct_I.unpack(str[start:end])
01923 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices = []
01924 for i in range(0, length):
01925 val1 = geometry_msgs.msg.Point()
01926 _x = val1
01927 start = end
01928 end += 24
01929 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01930 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices.append(val1)
01931 _x = self
01932 start = end
01933 end += 12
01934 (_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01935 start = end
01936 end += 4
01937 (length,) = _struct_I.unpack(str[start:end])
01938 start = end
01939 end += length
01940 if python3:
01941 self.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end].decode('utf-8')
01942 else:
01943 self.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
01944 _x = self
01945 start = end
01946 end += 68
01947 (_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.goal.motion_plan_request.start_state.joint_state.header.seq, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
01948 start = end
01949 end += 4
01950 (length,) = _struct_I.unpack(str[start:end])
01951 start = end
01952 end += length
01953 if python3:
01954 self.goal.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
01955 else:
01956 self.goal.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end]
01957 start = end
01958 end += 4
01959 (length,) = _struct_I.unpack(str[start:end])
01960 self.goal.motion_plan_request.start_state.joint_state.name = []
01961 for i in range(0, length):
01962 start = end
01963 end += 4
01964 (length,) = _struct_I.unpack(str[start:end])
01965 start = end
01966 end += length
01967 if python3:
01968 val1 = str[start:end].decode('utf-8')
01969 else:
01970 val1 = str[start:end]
01971 self.goal.motion_plan_request.start_state.joint_state.name.append(val1)
01972 start = end
01973 end += 4
01974 (length,) = _struct_I.unpack(str[start:end])
01975 pattern = '<%sd'%length
01976 start = end
01977 end += struct.calcsize(pattern)
01978 self.goal.motion_plan_request.start_state.joint_state.position = struct.unpack(pattern, str[start:end])
01979 start = end
01980 end += 4
01981 (length,) = _struct_I.unpack(str[start:end])
01982 pattern = '<%sd'%length
01983 start = end
01984 end += struct.calcsize(pattern)
01985 self.goal.motion_plan_request.start_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
01986 start = end
01987 end += 4
01988 (length,) = _struct_I.unpack(str[start:end])
01989 pattern = '<%sd'%length
01990 start = end
01991 end += struct.calcsize(pattern)
01992 self.goal.motion_plan_request.start_state.joint_state.effort = struct.unpack(pattern, str[start:end])
01993 _x = self
01994 start = end
01995 end += 8
01996 (_x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01997 start = end
01998 end += 4
01999 (length,) = _struct_I.unpack(str[start:end])
02000 self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names = []
02001 for i in range(0, length):
02002 start = end
02003 end += 4
02004 (length,) = _struct_I.unpack(str[start:end])
02005 start = end
02006 end += length
02007 if python3:
02008 val1 = str[start:end].decode('utf-8')
02009 else:
02010 val1 = str[start:end]
02011 self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names.append(val1)
02012 start = end
02013 end += 4
02014 (length,) = _struct_I.unpack(str[start:end])
02015 self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = []
02016 for i in range(0, length):
02017 start = end
02018 end += 4
02019 (length,) = _struct_I.unpack(str[start:end])
02020 start = end
02021 end += length
02022 if python3:
02023 val1 = str[start:end].decode('utf-8')
02024 else:
02025 val1 = str[start:end]
02026 self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids.append(val1)
02027 start = end
02028 end += 4
02029 (length,) = _struct_I.unpack(str[start:end])
02030 self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = []
02031 for i in range(0, length):
02032 start = end
02033 end += 4
02034 (length,) = _struct_I.unpack(str[start:end])
02035 start = end
02036 end += length
02037 if python3:
02038 val1 = str[start:end].decode('utf-8')
02039 else:
02040 val1 = str[start:end]
02041 self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
02042 start = end
02043 end += 4
02044 (length,) = _struct_I.unpack(str[start:end])
02045 self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses = []
02046 for i in range(0, length):
02047 val1 = geometry_msgs.msg.Pose()
02048 _v101 = val1.position
02049 _x = _v101
02050 start = end
02051 end += 24
02052 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02053 _v102 = val1.orientation
02054 _x = _v102
02055 start = end
02056 end += 32
02057 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02058 self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses.append(val1)
02059 start = end
02060 end += 4
02061 (length,) = _struct_I.unpack(str[start:end])
02062 self.goal.motion_plan_request.goal_constraints.joint_constraints = []
02063 for i in range(0, length):
02064 val1 = arm_navigation_msgs.msg.JointConstraint()
02065 start = end
02066 end += 4
02067 (length,) = _struct_I.unpack(str[start:end])
02068 start = end
02069 end += length
02070 if python3:
02071 val1.joint_name = str[start:end].decode('utf-8')
02072 else:
02073 val1.joint_name = str[start:end]
02074 _x = val1
02075 start = end
02076 end += 32
02077 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02078 self.goal.motion_plan_request.goal_constraints.joint_constraints.append(val1)
02079 start = end
02080 end += 4
02081 (length,) = _struct_I.unpack(str[start:end])
02082 self.goal.motion_plan_request.goal_constraints.position_constraints = []
02083 for i in range(0, length):
02084 val1 = arm_navigation_msgs.msg.PositionConstraint()
02085 _v103 = val1.header
02086 start = end
02087 end += 4
02088 (_v103.seq,) = _struct_I.unpack(str[start:end])
02089 _v104 = _v103.stamp
02090 _x = _v104
02091 start = end
02092 end += 8
02093 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02094 start = end
02095 end += 4
02096 (length,) = _struct_I.unpack(str[start:end])
02097 start = end
02098 end += length
02099 if python3:
02100 _v103.frame_id = str[start:end].decode('utf-8')
02101 else:
02102 _v103.frame_id = str[start:end]
02103 start = end
02104 end += 4
02105 (length,) = _struct_I.unpack(str[start:end])
02106 start = end
02107 end += length
02108 if python3:
02109 val1.link_name = str[start:end].decode('utf-8')
02110 else:
02111 val1.link_name = str[start:end]
02112 _v105 = val1.target_point_offset
02113 _x = _v105
02114 start = end
02115 end += 24
02116 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02117 _v106 = val1.position
02118 _x = _v106
02119 start = end
02120 end += 24
02121 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02122 _v107 = val1.constraint_region_shape
02123 start = end
02124 end += 1
02125 (_v107.type,) = _struct_b.unpack(str[start:end])
02126 start = end
02127 end += 4
02128 (length,) = _struct_I.unpack(str[start:end])
02129 pattern = '<%sd'%length
02130 start = end
02131 end += struct.calcsize(pattern)
02132 _v107.dimensions = struct.unpack(pattern, str[start:end])
02133 start = end
02134 end += 4
02135 (length,) = _struct_I.unpack(str[start:end])
02136 pattern = '<%si'%length
02137 start = end
02138 end += struct.calcsize(pattern)
02139 _v107.triangles = struct.unpack(pattern, str[start:end])
02140 start = end
02141 end += 4
02142 (length,) = _struct_I.unpack(str[start:end])
02143 _v107.vertices = []
02144 for i in range(0, length):
02145 val3 = geometry_msgs.msg.Point()
02146 _x = val3
02147 start = end
02148 end += 24
02149 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02150 _v107.vertices.append(val3)
02151 _v108 = val1.constraint_region_orientation
02152 _x = _v108
02153 start = end
02154 end += 32
02155 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02156 start = end
02157 end += 8
02158 (val1.weight,) = _struct_d.unpack(str[start:end])
02159 self.goal.motion_plan_request.goal_constraints.position_constraints.append(val1)
02160 start = end
02161 end += 4
02162 (length,) = _struct_I.unpack(str[start:end])
02163 self.goal.motion_plan_request.goal_constraints.orientation_constraints = []
02164 for i in range(0, length):
02165 val1 = arm_navigation_msgs.msg.OrientationConstraint()
02166 _v109 = val1.header
02167 start = end
02168 end += 4
02169 (_v109.seq,) = _struct_I.unpack(str[start:end])
02170 _v110 = _v109.stamp
02171 _x = _v110
02172 start = end
02173 end += 8
02174 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02175 start = end
02176 end += 4
02177 (length,) = _struct_I.unpack(str[start:end])
02178 start = end
02179 end += length
02180 if python3:
02181 _v109.frame_id = str[start:end].decode('utf-8')
02182 else:
02183 _v109.frame_id = str[start:end]
02184 start = end
02185 end += 4
02186 (length,) = _struct_I.unpack(str[start:end])
02187 start = end
02188 end += length
02189 if python3:
02190 val1.link_name = str[start:end].decode('utf-8')
02191 else:
02192 val1.link_name = str[start:end]
02193 start = end
02194 end += 4
02195 (val1.type,) = _struct_i.unpack(str[start:end])
02196 _v111 = val1.orientation
02197 _x = _v111
02198 start = end
02199 end += 32
02200 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02201 _x = val1
02202 start = end
02203 end += 32
02204 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02205 self.goal.motion_plan_request.goal_constraints.orientation_constraints.append(val1)
02206 start = end
02207 end += 4
02208 (length,) = _struct_I.unpack(str[start:end])
02209 self.goal.motion_plan_request.goal_constraints.visibility_constraints = []
02210 for i in range(0, length):
02211 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02212 _v112 = val1.header
02213 start = end
02214 end += 4
02215 (_v112.seq,) = _struct_I.unpack(str[start:end])
02216 _v113 = _v112.stamp
02217 _x = _v113
02218 start = end
02219 end += 8
02220 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02221 start = end
02222 end += 4
02223 (length,) = _struct_I.unpack(str[start:end])
02224 start = end
02225 end += length
02226 if python3:
02227 _v112.frame_id = str[start:end].decode('utf-8')
02228 else:
02229 _v112.frame_id = str[start:end]
02230 _v114 = val1.target
02231 _v115 = _v114.header
02232 start = end
02233 end += 4
02234 (_v115.seq,) = _struct_I.unpack(str[start:end])
02235 _v116 = _v115.stamp
02236 _x = _v116
02237 start = end
02238 end += 8
02239 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02240 start = end
02241 end += 4
02242 (length,) = _struct_I.unpack(str[start:end])
02243 start = end
02244 end += length
02245 if python3:
02246 _v115.frame_id = str[start:end].decode('utf-8')
02247 else:
02248 _v115.frame_id = str[start:end]
02249 _v117 = _v114.point
02250 _x = _v117
02251 start = end
02252 end += 24
02253 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02254 _v118 = val1.sensor_pose
02255 _v119 = _v118.header
02256 start = end
02257 end += 4
02258 (_v119.seq,) = _struct_I.unpack(str[start:end])
02259 _v120 = _v119.stamp
02260 _x = _v120
02261 start = end
02262 end += 8
02263 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02264 start = end
02265 end += 4
02266 (length,) = _struct_I.unpack(str[start:end])
02267 start = end
02268 end += length
02269 if python3:
02270 _v119.frame_id = str[start:end].decode('utf-8')
02271 else:
02272 _v119.frame_id = str[start:end]
02273 _v121 = _v118.pose
02274 _v122 = _v121.position
02275 _x = _v122
02276 start = end
02277 end += 24
02278 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02279 _v123 = _v121.orientation
02280 _x = _v123
02281 start = end
02282 end += 32
02283 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02284 start = end
02285 end += 8
02286 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02287 self.goal.motion_plan_request.goal_constraints.visibility_constraints.append(val1)
02288 start = end
02289 end += 4
02290 (length,) = _struct_I.unpack(str[start:end])
02291 self.goal.motion_plan_request.path_constraints.joint_constraints = []
02292 for i in range(0, length):
02293 val1 = arm_navigation_msgs.msg.JointConstraint()
02294 start = end
02295 end += 4
02296 (length,) = _struct_I.unpack(str[start:end])
02297 start = end
02298 end += length
02299 if python3:
02300 val1.joint_name = str[start:end].decode('utf-8')
02301 else:
02302 val1.joint_name = str[start:end]
02303 _x = val1
02304 start = end
02305 end += 32
02306 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02307 self.goal.motion_plan_request.path_constraints.joint_constraints.append(val1)
02308 start = end
02309 end += 4
02310 (length,) = _struct_I.unpack(str[start:end])
02311 self.goal.motion_plan_request.path_constraints.position_constraints = []
02312 for i in range(0, length):
02313 val1 = arm_navigation_msgs.msg.PositionConstraint()
02314 _v124 = val1.header
02315 start = end
02316 end += 4
02317 (_v124.seq,) = _struct_I.unpack(str[start:end])
02318 _v125 = _v124.stamp
02319 _x = _v125
02320 start = end
02321 end += 8
02322 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02323 start = end
02324 end += 4
02325 (length,) = _struct_I.unpack(str[start:end])
02326 start = end
02327 end += length
02328 if python3:
02329 _v124.frame_id = str[start:end].decode('utf-8')
02330 else:
02331 _v124.frame_id = str[start:end]
02332 start = end
02333 end += 4
02334 (length,) = _struct_I.unpack(str[start:end])
02335 start = end
02336 end += length
02337 if python3:
02338 val1.link_name = str[start:end].decode('utf-8')
02339 else:
02340 val1.link_name = str[start:end]
02341 _v126 = val1.target_point_offset
02342 _x = _v126
02343 start = end
02344 end += 24
02345 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02346 _v127 = val1.position
02347 _x = _v127
02348 start = end
02349 end += 24
02350 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02351 _v128 = val1.constraint_region_shape
02352 start = end
02353 end += 1
02354 (_v128.type,) = _struct_b.unpack(str[start:end])
02355 start = end
02356 end += 4
02357 (length,) = _struct_I.unpack(str[start:end])
02358 pattern = '<%sd'%length
02359 start = end
02360 end += struct.calcsize(pattern)
02361 _v128.dimensions = struct.unpack(pattern, str[start:end])
02362 start = end
02363 end += 4
02364 (length,) = _struct_I.unpack(str[start:end])
02365 pattern = '<%si'%length
02366 start = end
02367 end += struct.calcsize(pattern)
02368 _v128.triangles = struct.unpack(pattern, str[start:end])
02369 start = end
02370 end += 4
02371 (length,) = _struct_I.unpack(str[start:end])
02372 _v128.vertices = []
02373 for i in range(0, length):
02374 val3 = geometry_msgs.msg.Point()
02375 _x = val3
02376 start = end
02377 end += 24
02378 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02379 _v128.vertices.append(val3)
02380 _v129 = val1.constraint_region_orientation
02381 _x = _v129
02382 start = end
02383 end += 32
02384 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02385 start = end
02386 end += 8
02387 (val1.weight,) = _struct_d.unpack(str[start:end])
02388 self.goal.motion_plan_request.path_constraints.position_constraints.append(val1)
02389 start = end
02390 end += 4
02391 (length,) = _struct_I.unpack(str[start:end])
02392 self.goal.motion_plan_request.path_constraints.orientation_constraints = []
02393 for i in range(0, length):
02394 val1 = arm_navigation_msgs.msg.OrientationConstraint()
02395 _v130 = val1.header
02396 start = end
02397 end += 4
02398 (_v130.seq,) = _struct_I.unpack(str[start:end])
02399 _v131 = _v130.stamp
02400 _x = _v131
02401 start = end
02402 end += 8
02403 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02404 start = end
02405 end += 4
02406 (length,) = _struct_I.unpack(str[start:end])
02407 start = end
02408 end += length
02409 if python3:
02410 _v130.frame_id = str[start:end].decode('utf-8')
02411 else:
02412 _v130.frame_id = str[start:end]
02413 start = end
02414 end += 4
02415 (length,) = _struct_I.unpack(str[start:end])
02416 start = end
02417 end += length
02418 if python3:
02419 val1.link_name = str[start:end].decode('utf-8')
02420 else:
02421 val1.link_name = str[start:end]
02422 start = end
02423 end += 4
02424 (val1.type,) = _struct_i.unpack(str[start:end])
02425 _v132 = val1.orientation
02426 _x = _v132
02427 start = end
02428 end += 32
02429 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02430 _x = val1
02431 start = end
02432 end += 32
02433 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02434 self.goal.motion_plan_request.path_constraints.orientation_constraints.append(val1)
02435 start = end
02436 end += 4
02437 (length,) = _struct_I.unpack(str[start:end])
02438 self.goal.motion_plan_request.path_constraints.visibility_constraints = []
02439 for i in range(0, length):
02440 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02441 _v133 = val1.header
02442 start = end
02443 end += 4
02444 (_v133.seq,) = _struct_I.unpack(str[start:end])
02445 _v134 = _v133.stamp
02446 _x = _v134
02447 start = end
02448 end += 8
02449 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02450 start = end
02451 end += 4
02452 (length,) = _struct_I.unpack(str[start:end])
02453 start = end
02454 end += length
02455 if python3:
02456 _v133.frame_id = str[start:end].decode('utf-8')
02457 else:
02458 _v133.frame_id = str[start:end]
02459 _v135 = val1.target
02460 _v136 = _v135.header
02461 start = end
02462 end += 4
02463 (_v136.seq,) = _struct_I.unpack(str[start:end])
02464 _v137 = _v136.stamp
02465 _x = _v137
02466 start = end
02467 end += 8
02468 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02469 start = end
02470 end += 4
02471 (length,) = _struct_I.unpack(str[start:end])
02472 start = end
02473 end += length
02474 if python3:
02475 _v136.frame_id = str[start:end].decode('utf-8')
02476 else:
02477 _v136.frame_id = str[start:end]
02478 _v138 = _v135.point
02479 _x = _v138
02480 start = end
02481 end += 24
02482 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02483 _v139 = val1.sensor_pose
02484 _v140 = _v139.header
02485 start = end
02486 end += 4
02487 (_v140.seq,) = _struct_I.unpack(str[start:end])
02488 _v141 = _v140.stamp
02489 _x = _v141
02490 start = end
02491 end += 8
02492 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02493 start = end
02494 end += 4
02495 (length,) = _struct_I.unpack(str[start:end])
02496 start = end
02497 end += length
02498 if python3:
02499 _v140.frame_id = str[start:end].decode('utf-8')
02500 else:
02501 _v140.frame_id = str[start:end]
02502 _v142 = _v139.pose
02503 _v143 = _v142.position
02504 _x = _v143
02505 start = end
02506 end += 24
02507 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02508 _v144 = _v142.orientation
02509 _x = _v144
02510 start = end
02511 end += 32
02512 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02513 start = end
02514 end += 8
02515 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02516 self.goal.motion_plan_request.path_constraints.visibility_constraints.append(val1)
02517 start = end
02518 end += 4
02519 (length,) = _struct_I.unpack(str[start:end])
02520 start = end
02521 end += length
02522 if python3:
02523 self.goal.motion_plan_request.planner_id = str[start:end].decode('utf-8')
02524 else:
02525 self.goal.motion_plan_request.planner_id = str[start:end]
02526 start = end
02527 end += 4
02528 (length,) = _struct_I.unpack(str[start:end])
02529 start = end
02530 end += length
02531 if python3:
02532 self.goal.motion_plan_request.group_name = str[start:end].decode('utf-8')
02533 else:
02534 self.goal.motion_plan_request.group_name = str[start:end]
02535 _x = self
02536 start = end
02537 end += 28
02538 (_x.goal.motion_plan_request.num_planning_attempts, _x.goal.motion_plan_request.allowed_planning_time.secs, _x.goal.motion_plan_request.allowed_planning_time.nsecs, _x.goal.motion_plan_request.expected_path_duration.secs, _x.goal.motion_plan_request.expected_path_duration.nsecs, _x.goal.motion_plan_request.expected_path_dt.secs, _x.goal.motion_plan_request.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
02539 start = end
02540 end += 4
02541 (length,) = _struct_I.unpack(str[start:end])
02542 self.goal.operations.collision_operations = []
02543 for i in range(0, length):
02544 val1 = arm_navigation_msgs.msg.CollisionOperation()
02545 start = end
02546 end += 4
02547 (length,) = _struct_I.unpack(str[start:end])
02548 start = end
02549 end += length
02550 if python3:
02551 val1.object1 = str[start:end].decode('utf-8')
02552 else:
02553 val1.object1 = str[start:end]
02554 start = end
02555 end += 4
02556 (length,) = _struct_I.unpack(str[start:end])
02557 start = end
02558 end += length
02559 if python3:
02560 val1.object2 = str[start:end].decode('utf-8')
02561 else:
02562 val1.object2 = str[start:end]
02563 _x = val1
02564 start = end
02565 end += 12
02566 (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
02567 self.goal.operations.collision_operations.append(val1)
02568 _x = self
02569 start = end
02570 end += 4
02571 (_x.goal.accept_partial_plans, _x.goal.accept_invalid_goals, _x.goal.disable_ik, _x.goal.disable_collision_monitoring,) = _struct_4B.unpack(str[start:end])
02572 self.goal.accept_partial_plans = bool(self.goal.accept_partial_plans)
02573 self.goal.accept_invalid_goals = bool(self.goal.accept_invalid_goals)
02574 self.goal.disable_ik = bool(self.goal.disable_ik)
02575 self.goal.disable_collision_monitoring = bool(self.goal.disable_collision_monitoring)
02576 return self
02577 except struct.error as e:
02578 raise genpy.DeserializationError(e)
02579
02580
02581 def serialize_numpy(self, buff, numpy):
02582 """
02583 serialize message with numpy array types into buffer
02584 :param buff: buffer, ``StringIO``
02585 :param numpy: numpy python module
02586 """
02587 try:
02588 _x = self
02589 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
02590 _x = self.header.frame_id
02591 length = len(_x)
02592 if python3 or type(_x) == unicode:
02593 _x = _x.encode('utf-8')
02594 length = len(_x)
02595 buff.write(struct.pack('<I%ss'%length, length, _x))
02596 _x = self
02597 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
02598 _x = self.goal_id.id
02599 length = len(_x)
02600 if python3 or type(_x) == unicode:
02601 _x = _x.encode('utf-8')
02602 length = len(_x)
02603 buff.write(struct.pack('<I%ss'%length, length, _x))
02604 _x = self.goal.planner_service_name
02605 length = len(_x)
02606 if python3 or type(_x) == unicode:
02607 _x = _x.encode('utf-8')
02608 length = len(_x)
02609 buff.write(struct.pack('<I%ss'%length, length, _x))
02610 _x = self
02611 buff.write(_struct_3I.pack(_x.goal.planning_scene_diff.robot_state.joint_state.header.seq, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs))
02612 _x = self.goal.planning_scene_diff.robot_state.joint_state.header.frame_id
02613 length = len(_x)
02614 if python3 or type(_x) == unicode:
02615 _x = _x.encode('utf-8')
02616 length = len(_x)
02617 buff.write(struct.pack('<I%ss'%length, length, _x))
02618 length = len(self.goal.planning_scene_diff.robot_state.joint_state.name)
02619 buff.write(_struct_I.pack(length))
02620 for val1 in self.goal.planning_scene_diff.robot_state.joint_state.name:
02621 length = len(val1)
02622 if python3 or type(val1) == unicode:
02623 val1 = val1.encode('utf-8')
02624 length = len(val1)
02625 buff.write(struct.pack('<I%ss'%length, length, val1))
02626 length = len(self.goal.planning_scene_diff.robot_state.joint_state.position)
02627 buff.write(_struct_I.pack(length))
02628 pattern = '<%sd'%length
02629 buff.write(self.goal.planning_scene_diff.robot_state.joint_state.position.tostring())
02630 length = len(self.goal.planning_scene_diff.robot_state.joint_state.velocity)
02631 buff.write(_struct_I.pack(length))
02632 pattern = '<%sd'%length
02633 buff.write(self.goal.planning_scene_diff.robot_state.joint_state.velocity.tostring())
02634 length = len(self.goal.planning_scene_diff.robot_state.joint_state.effort)
02635 buff.write(_struct_I.pack(length))
02636 pattern = '<%sd'%length
02637 buff.write(self.goal.planning_scene_diff.robot_state.joint_state.effort.tostring())
02638 _x = self
02639 buff.write(_struct_2I.pack(_x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs))
02640 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names)
02641 buff.write(_struct_I.pack(length))
02642 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names:
02643 length = len(val1)
02644 if python3 or type(val1) == unicode:
02645 val1 = val1.encode('utf-8')
02646 length = len(val1)
02647 buff.write(struct.pack('<I%ss'%length, length, val1))
02648 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids)
02649 buff.write(_struct_I.pack(length))
02650 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids:
02651 length = len(val1)
02652 if python3 or type(val1) == unicode:
02653 val1 = val1.encode('utf-8')
02654 length = len(val1)
02655 buff.write(struct.pack('<I%ss'%length, length, val1))
02656 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids)
02657 buff.write(_struct_I.pack(length))
02658 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids:
02659 length = len(val1)
02660 if python3 or type(val1) == unicode:
02661 val1 = val1.encode('utf-8')
02662 length = len(val1)
02663 buff.write(struct.pack('<I%ss'%length, length, val1))
02664 length = len(self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses)
02665 buff.write(_struct_I.pack(length))
02666 for val1 in self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses:
02667 _v145 = val1.position
02668 _x = _v145
02669 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02670 _v146 = val1.orientation
02671 _x = _v146
02672 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02673 length = len(self.goal.planning_scene_diff.fixed_frame_transforms)
02674 buff.write(_struct_I.pack(length))
02675 for val1 in self.goal.planning_scene_diff.fixed_frame_transforms:
02676 _v147 = val1.header
02677 buff.write(_struct_I.pack(_v147.seq))
02678 _v148 = _v147.stamp
02679 _x = _v148
02680 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02681 _x = _v147.frame_id
02682 length = len(_x)
02683 if python3 or type(_x) == unicode:
02684 _x = _x.encode('utf-8')
02685 length = len(_x)
02686 buff.write(struct.pack('<I%ss'%length, length, _x))
02687 _x = val1.child_frame_id
02688 length = len(_x)
02689 if python3 or type(_x) == unicode:
02690 _x = _x.encode('utf-8')
02691 length = len(_x)
02692 buff.write(struct.pack('<I%ss'%length, length, _x))
02693 _v149 = val1.transform
02694 _v150 = _v149.translation
02695 _x = _v150
02696 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02697 _v151 = _v149.rotation
02698 _x = _v151
02699 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02700 length = len(self.goal.planning_scene_diff.allowed_collision_matrix.link_names)
02701 buff.write(_struct_I.pack(length))
02702 for val1 in self.goal.planning_scene_diff.allowed_collision_matrix.link_names:
02703 length = len(val1)
02704 if python3 or type(val1) == unicode:
02705 val1 = val1.encode('utf-8')
02706 length = len(val1)
02707 buff.write(struct.pack('<I%ss'%length, length, val1))
02708 length = len(self.goal.planning_scene_diff.allowed_collision_matrix.entries)
02709 buff.write(_struct_I.pack(length))
02710 for val1 in self.goal.planning_scene_diff.allowed_collision_matrix.entries:
02711 length = len(val1.enabled)
02712 buff.write(_struct_I.pack(length))
02713 pattern = '<%sB'%length
02714 buff.write(val1.enabled.tostring())
02715 length = len(self.goal.planning_scene_diff.allowed_contacts)
02716 buff.write(_struct_I.pack(length))
02717 for val1 in self.goal.planning_scene_diff.allowed_contacts:
02718 _x = val1.name
02719 length = len(_x)
02720 if python3 or type(_x) == unicode:
02721 _x = _x.encode('utf-8')
02722 length = len(_x)
02723 buff.write(struct.pack('<I%ss'%length, length, _x))
02724 _v152 = val1.shape
02725 buff.write(_struct_b.pack(_v152.type))
02726 length = len(_v152.dimensions)
02727 buff.write(_struct_I.pack(length))
02728 pattern = '<%sd'%length
02729 buff.write(_v152.dimensions.tostring())
02730 length = len(_v152.triangles)
02731 buff.write(_struct_I.pack(length))
02732 pattern = '<%si'%length
02733 buff.write(_v152.triangles.tostring())
02734 length = len(_v152.vertices)
02735 buff.write(_struct_I.pack(length))
02736 for val3 in _v152.vertices:
02737 _x = val3
02738 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02739 _v153 = val1.pose_stamped
02740 _v154 = _v153.header
02741 buff.write(_struct_I.pack(_v154.seq))
02742 _v155 = _v154.stamp
02743 _x = _v155
02744 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02745 _x = _v154.frame_id
02746 length = len(_x)
02747 if python3 or type(_x) == unicode:
02748 _x = _x.encode('utf-8')
02749 length = len(_x)
02750 buff.write(struct.pack('<I%ss'%length, length, _x))
02751 _v156 = _v153.pose
02752 _v157 = _v156.position
02753 _x = _v157
02754 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02755 _v158 = _v156.orientation
02756 _x = _v158
02757 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02758 length = len(val1.link_names)
02759 buff.write(_struct_I.pack(length))
02760 for val2 in val1.link_names:
02761 length = len(val2)
02762 if python3 or type(val2) == unicode:
02763 val2 = val2.encode('utf-8')
02764 length = len(val2)
02765 buff.write(struct.pack('<I%ss'%length, length, val2))
02766 buff.write(_struct_d.pack(val1.penetration_depth))
02767 length = len(self.goal.planning_scene_diff.link_padding)
02768 buff.write(_struct_I.pack(length))
02769 for val1 in self.goal.planning_scene_diff.link_padding:
02770 _x = val1.link_name
02771 length = len(_x)
02772 if python3 or type(_x) == unicode:
02773 _x = _x.encode('utf-8')
02774 length = len(_x)
02775 buff.write(struct.pack('<I%ss'%length, length, _x))
02776 buff.write(_struct_d.pack(val1.padding))
02777 length = len(self.goal.planning_scene_diff.collision_objects)
02778 buff.write(_struct_I.pack(length))
02779 for val1 in self.goal.planning_scene_diff.collision_objects:
02780 _v159 = val1.header
02781 buff.write(_struct_I.pack(_v159.seq))
02782 _v160 = _v159.stamp
02783 _x = _v160
02784 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02785 _x = _v159.frame_id
02786 length = len(_x)
02787 if python3 or type(_x) == unicode:
02788 _x = _x.encode('utf-8')
02789 length = len(_x)
02790 buff.write(struct.pack('<I%ss'%length, length, _x))
02791 _x = val1.id
02792 length = len(_x)
02793 if python3 or type(_x) == unicode:
02794 _x = _x.encode('utf-8')
02795 length = len(_x)
02796 buff.write(struct.pack('<I%ss'%length, length, _x))
02797 buff.write(_struct_f.pack(val1.padding))
02798 _v161 = val1.operation
02799 buff.write(_struct_b.pack(_v161.operation))
02800 length = len(val1.shapes)
02801 buff.write(_struct_I.pack(length))
02802 for val2 in val1.shapes:
02803 buff.write(_struct_b.pack(val2.type))
02804 length = len(val2.dimensions)
02805 buff.write(_struct_I.pack(length))
02806 pattern = '<%sd'%length
02807 buff.write(val2.dimensions.tostring())
02808 length = len(val2.triangles)
02809 buff.write(_struct_I.pack(length))
02810 pattern = '<%si'%length
02811 buff.write(val2.triangles.tostring())
02812 length = len(val2.vertices)
02813 buff.write(_struct_I.pack(length))
02814 for val3 in val2.vertices:
02815 _x = val3
02816 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02817 length = len(val1.poses)
02818 buff.write(_struct_I.pack(length))
02819 for val2 in val1.poses:
02820 _v162 = val2.position
02821 _x = _v162
02822 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02823 _v163 = val2.orientation
02824 _x = _v163
02825 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02826 length = len(self.goal.planning_scene_diff.attached_collision_objects)
02827 buff.write(_struct_I.pack(length))
02828 for val1 in self.goal.planning_scene_diff.attached_collision_objects:
02829 _x = val1.link_name
02830 length = len(_x)
02831 if python3 or type(_x) == unicode:
02832 _x = _x.encode('utf-8')
02833 length = len(_x)
02834 buff.write(struct.pack('<I%ss'%length, length, _x))
02835 _v164 = val1.object
02836 _v165 = _v164.header
02837 buff.write(_struct_I.pack(_v165.seq))
02838 _v166 = _v165.stamp
02839 _x = _v166
02840 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02841 _x = _v165.frame_id
02842 length = len(_x)
02843 if python3 or type(_x) == unicode:
02844 _x = _x.encode('utf-8')
02845 length = len(_x)
02846 buff.write(struct.pack('<I%ss'%length, length, _x))
02847 _x = _v164.id
02848 length = len(_x)
02849 if python3 or type(_x) == unicode:
02850 _x = _x.encode('utf-8')
02851 length = len(_x)
02852 buff.write(struct.pack('<I%ss'%length, length, _x))
02853 buff.write(_struct_f.pack(_v164.padding))
02854 _v167 = _v164.operation
02855 buff.write(_struct_b.pack(_v167.operation))
02856 length = len(_v164.shapes)
02857 buff.write(_struct_I.pack(length))
02858 for val3 in _v164.shapes:
02859 buff.write(_struct_b.pack(val3.type))
02860 length = len(val3.dimensions)
02861 buff.write(_struct_I.pack(length))
02862 pattern = '<%sd'%length
02863 buff.write(val3.dimensions.tostring())
02864 length = len(val3.triangles)
02865 buff.write(_struct_I.pack(length))
02866 pattern = '<%si'%length
02867 buff.write(val3.triangles.tostring())
02868 length = len(val3.vertices)
02869 buff.write(_struct_I.pack(length))
02870 for val4 in val3.vertices:
02871 _x = val4
02872 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02873 length = len(_v164.poses)
02874 buff.write(_struct_I.pack(length))
02875 for val3 in _v164.poses:
02876 _v168 = val3.position
02877 _x = _v168
02878 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02879 _v169 = val3.orientation
02880 _x = _v169
02881 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02882 length = len(val1.touch_links)
02883 buff.write(_struct_I.pack(length))
02884 for val2 in val1.touch_links:
02885 length = len(val2)
02886 if python3 or type(val2) == unicode:
02887 val2 = val2.encode('utf-8')
02888 length = len(val2)
02889 buff.write(struct.pack('<I%ss'%length, length, val2))
02890 _x = self
02891 buff.write(_struct_3I.pack(_x.goal.planning_scene_diff.collision_map.header.seq, _x.goal.planning_scene_diff.collision_map.header.stamp.secs, _x.goal.planning_scene_diff.collision_map.header.stamp.nsecs))
02892 _x = self.goal.planning_scene_diff.collision_map.header.frame_id
02893 length = len(_x)
02894 if python3 or type(_x) == unicode:
02895 _x = _x.encode('utf-8')
02896 length = len(_x)
02897 buff.write(struct.pack('<I%ss'%length, length, _x))
02898 length = len(self.goal.planning_scene_diff.collision_map.boxes)
02899 buff.write(_struct_I.pack(length))
02900 for val1 in self.goal.planning_scene_diff.collision_map.boxes:
02901 _v170 = val1.center
02902 _x = _v170
02903 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02904 _v171 = val1.extents
02905 _x = _v171
02906 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02907 _v172 = val1.axis
02908 _x = _v172
02909 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02910 buff.write(_struct_f.pack(val1.angle))
02911 buff.write(_struct_b.pack(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.type))
02912 length = len(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions)
02913 buff.write(_struct_I.pack(length))
02914 pattern = '<%sd'%length
02915 buff.write(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions.tostring())
02916 length = len(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.triangles)
02917 buff.write(_struct_I.pack(length))
02918 pattern = '<%si'%length
02919 buff.write(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.triangles.tostring())
02920 length = len(self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices)
02921 buff.write(_struct_I.pack(length))
02922 for val1 in self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices:
02923 _x = val1
02924 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02925 _x = self
02926 buff.write(_struct_3I.pack(_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
02927 _x = self.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id
02928 length = len(_x)
02929 if python3 or type(_x) == unicode:
02930 _x = _x.encode('utf-8')
02931 length = len(_x)
02932 buff.write(struct.pack('<I%ss'%length, length, _x))
02933 _x = self
02934 buff.write(_struct_7d3I.pack(_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.goal.motion_plan_request.start_state.joint_state.header.seq, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.nsecs))
02935 _x = self.goal.motion_plan_request.start_state.joint_state.header.frame_id
02936 length = len(_x)
02937 if python3 or type(_x) == unicode:
02938 _x = _x.encode('utf-8')
02939 length = len(_x)
02940 buff.write(struct.pack('<I%ss'%length, length, _x))
02941 length = len(self.goal.motion_plan_request.start_state.joint_state.name)
02942 buff.write(_struct_I.pack(length))
02943 for val1 in self.goal.motion_plan_request.start_state.joint_state.name:
02944 length = len(val1)
02945 if python3 or type(val1) == unicode:
02946 val1 = val1.encode('utf-8')
02947 length = len(val1)
02948 buff.write(struct.pack('<I%ss'%length, length, val1))
02949 length = len(self.goal.motion_plan_request.start_state.joint_state.position)
02950 buff.write(_struct_I.pack(length))
02951 pattern = '<%sd'%length
02952 buff.write(self.goal.motion_plan_request.start_state.joint_state.position.tostring())
02953 length = len(self.goal.motion_plan_request.start_state.joint_state.velocity)
02954 buff.write(_struct_I.pack(length))
02955 pattern = '<%sd'%length
02956 buff.write(self.goal.motion_plan_request.start_state.joint_state.velocity.tostring())
02957 length = len(self.goal.motion_plan_request.start_state.joint_state.effort)
02958 buff.write(_struct_I.pack(length))
02959 pattern = '<%sd'%length
02960 buff.write(self.goal.motion_plan_request.start_state.joint_state.effort.tostring())
02961 _x = self
02962 buff.write(_struct_2I.pack(_x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs))
02963 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names)
02964 buff.write(_struct_I.pack(length))
02965 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names:
02966 length = len(val1)
02967 if python3 or type(val1) == unicode:
02968 val1 = val1.encode('utf-8')
02969 length = len(val1)
02970 buff.write(struct.pack('<I%ss'%length, length, val1))
02971 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids)
02972 buff.write(_struct_I.pack(length))
02973 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids:
02974 length = len(val1)
02975 if python3 or type(val1) == unicode:
02976 val1 = val1.encode('utf-8')
02977 length = len(val1)
02978 buff.write(struct.pack('<I%ss'%length, length, val1))
02979 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids)
02980 buff.write(_struct_I.pack(length))
02981 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids:
02982 length = len(val1)
02983 if python3 or type(val1) == unicode:
02984 val1 = val1.encode('utf-8')
02985 length = len(val1)
02986 buff.write(struct.pack('<I%ss'%length, length, val1))
02987 length = len(self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses)
02988 buff.write(_struct_I.pack(length))
02989 for val1 in self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses:
02990 _v173 = val1.position
02991 _x = _v173
02992 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02993 _v174 = val1.orientation
02994 _x = _v174
02995 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02996 length = len(self.goal.motion_plan_request.goal_constraints.joint_constraints)
02997 buff.write(_struct_I.pack(length))
02998 for val1 in self.goal.motion_plan_request.goal_constraints.joint_constraints:
02999 _x = val1.joint_name
03000 length = len(_x)
03001 if python3 or type(_x) == unicode:
03002 _x = _x.encode('utf-8')
03003 length = len(_x)
03004 buff.write(struct.pack('<I%ss'%length, length, _x))
03005 _x = val1
03006 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
03007 length = len(self.goal.motion_plan_request.goal_constraints.position_constraints)
03008 buff.write(_struct_I.pack(length))
03009 for val1 in self.goal.motion_plan_request.goal_constraints.position_constraints:
03010 _v175 = val1.header
03011 buff.write(_struct_I.pack(_v175.seq))
03012 _v176 = _v175.stamp
03013 _x = _v176
03014 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03015 _x = _v175.frame_id
03016 length = len(_x)
03017 if python3 or type(_x) == unicode:
03018 _x = _x.encode('utf-8')
03019 length = len(_x)
03020 buff.write(struct.pack('<I%ss'%length, length, _x))
03021 _x = val1.link_name
03022 length = len(_x)
03023 if python3 or type(_x) == unicode:
03024 _x = _x.encode('utf-8')
03025 length = len(_x)
03026 buff.write(struct.pack('<I%ss'%length, length, _x))
03027 _v177 = val1.target_point_offset
03028 _x = _v177
03029 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03030 _v178 = val1.position
03031 _x = _v178
03032 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03033 _v179 = val1.constraint_region_shape
03034 buff.write(_struct_b.pack(_v179.type))
03035 length = len(_v179.dimensions)
03036 buff.write(_struct_I.pack(length))
03037 pattern = '<%sd'%length
03038 buff.write(_v179.dimensions.tostring())
03039 length = len(_v179.triangles)
03040 buff.write(_struct_I.pack(length))
03041 pattern = '<%si'%length
03042 buff.write(_v179.triangles.tostring())
03043 length = len(_v179.vertices)
03044 buff.write(_struct_I.pack(length))
03045 for val3 in _v179.vertices:
03046 _x = val3
03047 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03048 _v180 = val1.constraint_region_orientation
03049 _x = _v180
03050 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03051 buff.write(_struct_d.pack(val1.weight))
03052 length = len(self.goal.motion_plan_request.goal_constraints.orientation_constraints)
03053 buff.write(_struct_I.pack(length))
03054 for val1 in self.goal.motion_plan_request.goal_constraints.orientation_constraints:
03055 _v181 = val1.header
03056 buff.write(_struct_I.pack(_v181.seq))
03057 _v182 = _v181.stamp
03058 _x = _v182
03059 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03060 _x = _v181.frame_id
03061 length = len(_x)
03062 if python3 or type(_x) == unicode:
03063 _x = _x.encode('utf-8')
03064 length = len(_x)
03065 buff.write(struct.pack('<I%ss'%length, length, _x))
03066 _x = val1.link_name
03067 length = len(_x)
03068 if python3 or type(_x) == unicode:
03069 _x = _x.encode('utf-8')
03070 length = len(_x)
03071 buff.write(struct.pack('<I%ss'%length, length, _x))
03072 buff.write(_struct_i.pack(val1.type))
03073 _v183 = val1.orientation
03074 _x = _v183
03075 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03076 _x = val1
03077 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
03078 length = len(self.goal.motion_plan_request.goal_constraints.visibility_constraints)
03079 buff.write(_struct_I.pack(length))
03080 for val1 in self.goal.motion_plan_request.goal_constraints.visibility_constraints:
03081 _v184 = val1.header
03082 buff.write(_struct_I.pack(_v184.seq))
03083 _v185 = _v184.stamp
03084 _x = _v185
03085 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03086 _x = _v184.frame_id
03087 length = len(_x)
03088 if python3 or type(_x) == unicode:
03089 _x = _x.encode('utf-8')
03090 length = len(_x)
03091 buff.write(struct.pack('<I%ss'%length, length, _x))
03092 _v186 = val1.target
03093 _v187 = _v186.header
03094 buff.write(_struct_I.pack(_v187.seq))
03095 _v188 = _v187.stamp
03096 _x = _v188
03097 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03098 _x = _v187.frame_id
03099 length = len(_x)
03100 if python3 or type(_x) == unicode:
03101 _x = _x.encode('utf-8')
03102 length = len(_x)
03103 buff.write(struct.pack('<I%ss'%length, length, _x))
03104 _v189 = _v186.point
03105 _x = _v189
03106 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03107 _v190 = val1.sensor_pose
03108 _v191 = _v190.header
03109 buff.write(_struct_I.pack(_v191.seq))
03110 _v192 = _v191.stamp
03111 _x = _v192
03112 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03113 _x = _v191.frame_id
03114 length = len(_x)
03115 if python3 or type(_x) == unicode:
03116 _x = _x.encode('utf-8')
03117 length = len(_x)
03118 buff.write(struct.pack('<I%ss'%length, length, _x))
03119 _v193 = _v190.pose
03120 _v194 = _v193.position
03121 _x = _v194
03122 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03123 _v195 = _v193.orientation
03124 _x = _v195
03125 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03126 buff.write(_struct_d.pack(val1.absolute_tolerance))
03127 length = len(self.goal.motion_plan_request.path_constraints.joint_constraints)
03128 buff.write(_struct_I.pack(length))
03129 for val1 in self.goal.motion_plan_request.path_constraints.joint_constraints:
03130 _x = val1.joint_name
03131 length = len(_x)
03132 if python3 or type(_x) == unicode:
03133 _x = _x.encode('utf-8')
03134 length = len(_x)
03135 buff.write(struct.pack('<I%ss'%length, length, _x))
03136 _x = val1
03137 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
03138 length = len(self.goal.motion_plan_request.path_constraints.position_constraints)
03139 buff.write(_struct_I.pack(length))
03140 for val1 in self.goal.motion_plan_request.path_constraints.position_constraints:
03141 _v196 = val1.header
03142 buff.write(_struct_I.pack(_v196.seq))
03143 _v197 = _v196.stamp
03144 _x = _v197
03145 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03146 _x = _v196.frame_id
03147 length = len(_x)
03148 if python3 or type(_x) == unicode:
03149 _x = _x.encode('utf-8')
03150 length = len(_x)
03151 buff.write(struct.pack('<I%ss'%length, length, _x))
03152 _x = val1.link_name
03153 length = len(_x)
03154 if python3 or type(_x) == unicode:
03155 _x = _x.encode('utf-8')
03156 length = len(_x)
03157 buff.write(struct.pack('<I%ss'%length, length, _x))
03158 _v198 = val1.target_point_offset
03159 _x = _v198
03160 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03161 _v199 = val1.position
03162 _x = _v199
03163 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03164 _v200 = val1.constraint_region_shape
03165 buff.write(_struct_b.pack(_v200.type))
03166 length = len(_v200.dimensions)
03167 buff.write(_struct_I.pack(length))
03168 pattern = '<%sd'%length
03169 buff.write(_v200.dimensions.tostring())
03170 length = len(_v200.triangles)
03171 buff.write(_struct_I.pack(length))
03172 pattern = '<%si'%length
03173 buff.write(_v200.triangles.tostring())
03174 length = len(_v200.vertices)
03175 buff.write(_struct_I.pack(length))
03176 for val3 in _v200.vertices:
03177 _x = val3
03178 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03179 _v201 = val1.constraint_region_orientation
03180 _x = _v201
03181 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03182 buff.write(_struct_d.pack(val1.weight))
03183 length = len(self.goal.motion_plan_request.path_constraints.orientation_constraints)
03184 buff.write(_struct_I.pack(length))
03185 for val1 in self.goal.motion_plan_request.path_constraints.orientation_constraints:
03186 _v202 = val1.header
03187 buff.write(_struct_I.pack(_v202.seq))
03188 _v203 = _v202.stamp
03189 _x = _v203
03190 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03191 _x = _v202.frame_id
03192 length = len(_x)
03193 if python3 or type(_x) == unicode:
03194 _x = _x.encode('utf-8')
03195 length = len(_x)
03196 buff.write(struct.pack('<I%ss'%length, length, _x))
03197 _x = val1.link_name
03198 length = len(_x)
03199 if python3 or type(_x) == unicode:
03200 _x = _x.encode('utf-8')
03201 length = len(_x)
03202 buff.write(struct.pack('<I%ss'%length, length, _x))
03203 buff.write(_struct_i.pack(val1.type))
03204 _v204 = val1.orientation
03205 _x = _v204
03206 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03207 _x = val1
03208 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
03209 length = len(self.goal.motion_plan_request.path_constraints.visibility_constraints)
03210 buff.write(_struct_I.pack(length))
03211 for val1 in self.goal.motion_plan_request.path_constraints.visibility_constraints:
03212 _v205 = val1.header
03213 buff.write(_struct_I.pack(_v205.seq))
03214 _v206 = _v205.stamp
03215 _x = _v206
03216 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03217 _x = _v205.frame_id
03218 length = len(_x)
03219 if python3 or type(_x) == unicode:
03220 _x = _x.encode('utf-8')
03221 length = len(_x)
03222 buff.write(struct.pack('<I%ss'%length, length, _x))
03223 _v207 = val1.target
03224 _v208 = _v207.header
03225 buff.write(_struct_I.pack(_v208.seq))
03226 _v209 = _v208.stamp
03227 _x = _v209
03228 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03229 _x = _v208.frame_id
03230 length = len(_x)
03231 if python3 or type(_x) == unicode:
03232 _x = _x.encode('utf-8')
03233 length = len(_x)
03234 buff.write(struct.pack('<I%ss'%length, length, _x))
03235 _v210 = _v207.point
03236 _x = _v210
03237 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03238 _v211 = val1.sensor_pose
03239 _v212 = _v211.header
03240 buff.write(_struct_I.pack(_v212.seq))
03241 _v213 = _v212.stamp
03242 _x = _v213
03243 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03244 _x = _v212.frame_id
03245 length = len(_x)
03246 if python3 or type(_x) == unicode:
03247 _x = _x.encode('utf-8')
03248 length = len(_x)
03249 buff.write(struct.pack('<I%ss'%length, length, _x))
03250 _v214 = _v211.pose
03251 _v215 = _v214.position
03252 _x = _v215
03253 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03254 _v216 = _v214.orientation
03255 _x = _v216
03256 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03257 buff.write(_struct_d.pack(val1.absolute_tolerance))
03258 _x = self.goal.motion_plan_request.planner_id
03259 length = len(_x)
03260 if python3 or type(_x) == unicode:
03261 _x = _x.encode('utf-8')
03262 length = len(_x)
03263 buff.write(struct.pack('<I%ss'%length, length, _x))
03264 _x = self.goal.motion_plan_request.group_name
03265 length = len(_x)
03266 if python3 or type(_x) == unicode:
03267 _x = _x.encode('utf-8')
03268 length = len(_x)
03269 buff.write(struct.pack('<I%ss'%length, length, _x))
03270 _x = self
03271 buff.write(_struct_7i.pack(_x.goal.motion_plan_request.num_planning_attempts, _x.goal.motion_plan_request.allowed_planning_time.secs, _x.goal.motion_plan_request.allowed_planning_time.nsecs, _x.goal.motion_plan_request.expected_path_duration.secs, _x.goal.motion_plan_request.expected_path_duration.nsecs, _x.goal.motion_plan_request.expected_path_dt.secs, _x.goal.motion_plan_request.expected_path_dt.nsecs))
03272 length = len(self.goal.operations.collision_operations)
03273 buff.write(_struct_I.pack(length))
03274 for val1 in self.goal.operations.collision_operations:
03275 _x = val1.object1
03276 length = len(_x)
03277 if python3 or type(_x) == unicode:
03278 _x = _x.encode('utf-8')
03279 length = len(_x)
03280 buff.write(struct.pack('<I%ss'%length, length, _x))
03281 _x = val1.object2
03282 length = len(_x)
03283 if python3 or type(_x) == unicode:
03284 _x = _x.encode('utf-8')
03285 length = len(_x)
03286 buff.write(struct.pack('<I%ss'%length, length, _x))
03287 _x = val1
03288 buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
03289 _x = self
03290 buff.write(_struct_4B.pack(_x.goal.accept_partial_plans, _x.goal.accept_invalid_goals, _x.goal.disable_ik, _x.goal.disable_collision_monitoring))
03291 except struct.error as se: self._check_types(se)
03292 except TypeError as te: self._check_types(te)
03293
03294 def deserialize_numpy(self, str, numpy):
03295 """
03296 unpack serialized message in str into this message instance using numpy for array types
03297 :param str: byte array of serialized message, ``str``
03298 :param numpy: numpy python module
03299 """
03300 try:
03301 if self.header is None:
03302 self.header = std_msgs.msg.Header()
03303 if self.goal_id is None:
03304 self.goal_id = actionlib_msgs.msg.GoalID()
03305 if self.goal is None:
03306 self.goal = arm_navigation_msgs.msg.MoveArmGoal()
03307 end = 0
03308 _x = self
03309 start = end
03310 end += 12
03311 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03312 start = end
03313 end += 4
03314 (length,) = _struct_I.unpack(str[start:end])
03315 start = end
03316 end += length
03317 if python3:
03318 self.header.frame_id = str[start:end].decode('utf-8')
03319 else:
03320 self.header.frame_id = str[start:end]
03321 _x = self
03322 start = end
03323 end += 8
03324 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03325 start = end
03326 end += 4
03327 (length,) = _struct_I.unpack(str[start:end])
03328 start = end
03329 end += length
03330 if python3:
03331 self.goal_id.id = str[start:end].decode('utf-8')
03332 else:
03333 self.goal_id.id = str[start:end]
03334 start = end
03335 end += 4
03336 (length,) = _struct_I.unpack(str[start:end])
03337 start = end
03338 end += length
03339 if python3:
03340 self.goal.planner_service_name = str[start:end].decode('utf-8')
03341 else:
03342 self.goal.planner_service_name = str[start:end]
03343 _x = self
03344 start = end
03345 end += 12
03346 (_x.goal.planning_scene_diff.robot_state.joint_state.header.seq, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03347 start = end
03348 end += 4
03349 (length,) = _struct_I.unpack(str[start:end])
03350 start = end
03351 end += length
03352 if python3:
03353 self.goal.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
03354 else:
03355 self.goal.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end]
03356 start = end
03357 end += 4
03358 (length,) = _struct_I.unpack(str[start:end])
03359 self.goal.planning_scene_diff.robot_state.joint_state.name = []
03360 for i in range(0, length):
03361 start = end
03362 end += 4
03363 (length,) = _struct_I.unpack(str[start:end])
03364 start = end
03365 end += length
03366 if python3:
03367 val1 = str[start:end].decode('utf-8')
03368 else:
03369 val1 = str[start:end]
03370 self.goal.planning_scene_diff.robot_state.joint_state.name.append(val1)
03371 start = end
03372 end += 4
03373 (length,) = _struct_I.unpack(str[start:end])
03374 pattern = '<%sd'%length
03375 start = end
03376 end += struct.calcsize(pattern)
03377 self.goal.planning_scene_diff.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03378 start = end
03379 end += 4
03380 (length,) = _struct_I.unpack(str[start:end])
03381 pattern = '<%sd'%length
03382 start = end
03383 end += struct.calcsize(pattern)
03384 self.goal.planning_scene_diff.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03385 start = end
03386 end += 4
03387 (length,) = _struct_I.unpack(str[start:end])
03388 pattern = '<%sd'%length
03389 start = end
03390 end += struct.calcsize(pattern)
03391 self.goal.planning_scene_diff.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03392 _x = self
03393 start = end
03394 end += 8
03395 (_x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03396 start = end
03397 end += 4
03398 (length,) = _struct_I.unpack(str[start:end])
03399 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names = []
03400 for i in range(0, length):
03401 start = end
03402 end += 4
03403 (length,) = _struct_I.unpack(str[start:end])
03404 start = end
03405 end += length
03406 if python3:
03407 val1 = str[start:end].decode('utf-8')
03408 else:
03409 val1 = str[start:end]
03410 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names.append(val1)
03411 start = end
03412 end += 4
03413 (length,) = _struct_I.unpack(str[start:end])
03414 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids = []
03415 for i in range(0, length):
03416 start = end
03417 end += 4
03418 (length,) = _struct_I.unpack(str[start:end])
03419 start = end
03420 end += length
03421 if python3:
03422 val1 = str[start:end].decode('utf-8')
03423 else:
03424 val1 = str[start:end]
03425 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03426 start = end
03427 end += 4
03428 (length,) = _struct_I.unpack(str[start:end])
03429 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids = []
03430 for i in range(0, length):
03431 start = end
03432 end += 4
03433 (length,) = _struct_I.unpack(str[start:end])
03434 start = end
03435 end += length
03436 if python3:
03437 val1 = str[start:end].decode('utf-8')
03438 else:
03439 val1 = str[start:end]
03440 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03441 start = end
03442 end += 4
03443 (length,) = _struct_I.unpack(str[start:end])
03444 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses = []
03445 for i in range(0, length):
03446 val1 = geometry_msgs.msg.Pose()
03447 _v217 = val1.position
03448 _x = _v217
03449 start = end
03450 end += 24
03451 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03452 _v218 = val1.orientation
03453 _x = _v218
03454 start = end
03455 end += 32
03456 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03457 self.goal.planning_scene_diff.robot_state.multi_dof_joint_state.poses.append(val1)
03458 start = end
03459 end += 4
03460 (length,) = _struct_I.unpack(str[start:end])
03461 self.goal.planning_scene_diff.fixed_frame_transforms = []
03462 for i in range(0, length):
03463 val1 = geometry_msgs.msg.TransformStamped()
03464 _v219 = val1.header
03465 start = end
03466 end += 4
03467 (_v219.seq,) = _struct_I.unpack(str[start:end])
03468 _v220 = _v219.stamp
03469 _x = _v220
03470 start = end
03471 end += 8
03472 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03473 start = end
03474 end += 4
03475 (length,) = _struct_I.unpack(str[start:end])
03476 start = end
03477 end += length
03478 if python3:
03479 _v219.frame_id = str[start:end].decode('utf-8')
03480 else:
03481 _v219.frame_id = str[start:end]
03482 start = end
03483 end += 4
03484 (length,) = _struct_I.unpack(str[start:end])
03485 start = end
03486 end += length
03487 if python3:
03488 val1.child_frame_id = str[start:end].decode('utf-8')
03489 else:
03490 val1.child_frame_id = str[start:end]
03491 _v221 = val1.transform
03492 _v222 = _v221.translation
03493 _x = _v222
03494 start = end
03495 end += 24
03496 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03497 _v223 = _v221.rotation
03498 _x = _v223
03499 start = end
03500 end += 32
03501 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03502 self.goal.planning_scene_diff.fixed_frame_transforms.append(val1)
03503 start = end
03504 end += 4
03505 (length,) = _struct_I.unpack(str[start:end])
03506 self.goal.planning_scene_diff.allowed_collision_matrix.link_names = []
03507 for i in range(0, length):
03508 start = end
03509 end += 4
03510 (length,) = _struct_I.unpack(str[start:end])
03511 start = end
03512 end += length
03513 if python3:
03514 val1 = str[start:end].decode('utf-8')
03515 else:
03516 val1 = str[start:end]
03517 self.goal.planning_scene_diff.allowed_collision_matrix.link_names.append(val1)
03518 start = end
03519 end += 4
03520 (length,) = _struct_I.unpack(str[start:end])
03521 self.goal.planning_scene_diff.allowed_collision_matrix.entries = []
03522 for i in range(0, length):
03523 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
03524 start = end
03525 end += 4
03526 (length,) = _struct_I.unpack(str[start:end])
03527 pattern = '<%sB'%length
03528 start = end
03529 end += struct.calcsize(pattern)
03530 val1.enabled = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=length)
03531 val1.enabled = map(bool, val1.enabled)
03532 self.goal.planning_scene_diff.allowed_collision_matrix.entries.append(val1)
03533 start = end
03534 end += 4
03535 (length,) = _struct_I.unpack(str[start:end])
03536 self.goal.planning_scene_diff.allowed_contacts = []
03537 for i in range(0, length):
03538 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
03539 start = end
03540 end += 4
03541 (length,) = _struct_I.unpack(str[start:end])
03542 start = end
03543 end += length
03544 if python3:
03545 val1.name = str[start:end].decode('utf-8')
03546 else:
03547 val1.name = str[start:end]
03548 _v224 = val1.shape
03549 start = end
03550 end += 1
03551 (_v224.type,) = _struct_b.unpack(str[start:end])
03552 start = end
03553 end += 4
03554 (length,) = _struct_I.unpack(str[start:end])
03555 pattern = '<%sd'%length
03556 start = end
03557 end += struct.calcsize(pattern)
03558 _v224.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03559 start = end
03560 end += 4
03561 (length,) = _struct_I.unpack(str[start:end])
03562 pattern = '<%si'%length
03563 start = end
03564 end += struct.calcsize(pattern)
03565 _v224.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03566 start = end
03567 end += 4
03568 (length,) = _struct_I.unpack(str[start:end])
03569 _v224.vertices = []
03570 for i in range(0, length):
03571 val3 = geometry_msgs.msg.Point()
03572 _x = val3
03573 start = end
03574 end += 24
03575 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03576 _v224.vertices.append(val3)
03577 _v225 = val1.pose_stamped
03578 _v226 = _v225.header
03579 start = end
03580 end += 4
03581 (_v226.seq,) = _struct_I.unpack(str[start:end])
03582 _v227 = _v226.stamp
03583 _x = _v227
03584 start = end
03585 end += 8
03586 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03587 start = end
03588 end += 4
03589 (length,) = _struct_I.unpack(str[start:end])
03590 start = end
03591 end += length
03592 if python3:
03593 _v226.frame_id = str[start:end].decode('utf-8')
03594 else:
03595 _v226.frame_id = str[start:end]
03596 _v228 = _v225.pose
03597 _v229 = _v228.position
03598 _x = _v229
03599 start = end
03600 end += 24
03601 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03602 _v230 = _v228.orientation
03603 _x = _v230
03604 start = end
03605 end += 32
03606 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03607 start = end
03608 end += 4
03609 (length,) = _struct_I.unpack(str[start:end])
03610 val1.link_names = []
03611 for i in range(0, length):
03612 start = end
03613 end += 4
03614 (length,) = _struct_I.unpack(str[start:end])
03615 start = end
03616 end += length
03617 if python3:
03618 val2 = str[start:end].decode('utf-8')
03619 else:
03620 val2 = str[start:end]
03621 val1.link_names.append(val2)
03622 start = end
03623 end += 8
03624 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
03625 self.goal.planning_scene_diff.allowed_contacts.append(val1)
03626 start = end
03627 end += 4
03628 (length,) = _struct_I.unpack(str[start:end])
03629 self.goal.planning_scene_diff.link_padding = []
03630 for i in range(0, length):
03631 val1 = arm_navigation_msgs.msg.LinkPadding()
03632 start = end
03633 end += 4
03634 (length,) = _struct_I.unpack(str[start:end])
03635 start = end
03636 end += length
03637 if python3:
03638 val1.link_name = str[start:end].decode('utf-8')
03639 else:
03640 val1.link_name = str[start:end]
03641 start = end
03642 end += 8
03643 (val1.padding,) = _struct_d.unpack(str[start:end])
03644 self.goal.planning_scene_diff.link_padding.append(val1)
03645 start = end
03646 end += 4
03647 (length,) = _struct_I.unpack(str[start:end])
03648 self.goal.planning_scene_diff.collision_objects = []
03649 for i in range(0, length):
03650 val1 = arm_navigation_msgs.msg.CollisionObject()
03651 _v231 = val1.header
03652 start = end
03653 end += 4
03654 (_v231.seq,) = _struct_I.unpack(str[start:end])
03655 _v232 = _v231.stamp
03656 _x = _v232
03657 start = end
03658 end += 8
03659 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03660 start = end
03661 end += 4
03662 (length,) = _struct_I.unpack(str[start:end])
03663 start = end
03664 end += length
03665 if python3:
03666 _v231.frame_id = str[start:end].decode('utf-8')
03667 else:
03668 _v231.frame_id = str[start:end]
03669 start = end
03670 end += 4
03671 (length,) = _struct_I.unpack(str[start:end])
03672 start = end
03673 end += length
03674 if python3:
03675 val1.id = str[start:end].decode('utf-8')
03676 else:
03677 val1.id = str[start:end]
03678 start = end
03679 end += 4
03680 (val1.padding,) = _struct_f.unpack(str[start:end])
03681 _v233 = val1.operation
03682 start = end
03683 end += 1
03684 (_v233.operation,) = _struct_b.unpack(str[start:end])
03685 start = end
03686 end += 4
03687 (length,) = _struct_I.unpack(str[start:end])
03688 val1.shapes = []
03689 for i in range(0, length):
03690 val2 = arm_navigation_msgs.msg.Shape()
03691 start = end
03692 end += 1
03693 (val2.type,) = _struct_b.unpack(str[start:end])
03694 start = end
03695 end += 4
03696 (length,) = _struct_I.unpack(str[start:end])
03697 pattern = '<%sd'%length
03698 start = end
03699 end += struct.calcsize(pattern)
03700 val2.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03701 start = end
03702 end += 4
03703 (length,) = _struct_I.unpack(str[start:end])
03704 pattern = '<%si'%length
03705 start = end
03706 end += struct.calcsize(pattern)
03707 val2.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03708 start = end
03709 end += 4
03710 (length,) = _struct_I.unpack(str[start:end])
03711 val2.vertices = []
03712 for i in range(0, length):
03713 val3 = geometry_msgs.msg.Point()
03714 _x = val3
03715 start = end
03716 end += 24
03717 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03718 val2.vertices.append(val3)
03719 val1.shapes.append(val2)
03720 start = end
03721 end += 4
03722 (length,) = _struct_I.unpack(str[start:end])
03723 val1.poses = []
03724 for i in range(0, length):
03725 val2 = geometry_msgs.msg.Pose()
03726 _v234 = val2.position
03727 _x = _v234
03728 start = end
03729 end += 24
03730 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03731 _v235 = val2.orientation
03732 _x = _v235
03733 start = end
03734 end += 32
03735 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03736 val1.poses.append(val2)
03737 self.goal.planning_scene_diff.collision_objects.append(val1)
03738 start = end
03739 end += 4
03740 (length,) = _struct_I.unpack(str[start:end])
03741 self.goal.planning_scene_diff.attached_collision_objects = []
03742 for i in range(0, length):
03743 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
03744 start = end
03745 end += 4
03746 (length,) = _struct_I.unpack(str[start:end])
03747 start = end
03748 end += length
03749 if python3:
03750 val1.link_name = str[start:end].decode('utf-8')
03751 else:
03752 val1.link_name = str[start:end]
03753 _v236 = val1.object
03754 _v237 = _v236.header
03755 start = end
03756 end += 4
03757 (_v237.seq,) = _struct_I.unpack(str[start:end])
03758 _v238 = _v237.stamp
03759 _x = _v238
03760 start = end
03761 end += 8
03762 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03763 start = end
03764 end += 4
03765 (length,) = _struct_I.unpack(str[start:end])
03766 start = end
03767 end += length
03768 if python3:
03769 _v237.frame_id = str[start:end].decode('utf-8')
03770 else:
03771 _v237.frame_id = str[start:end]
03772 start = end
03773 end += 4
03774 (length,) = _struct_I.unpack(str[start:end])
03775 start = end
03776 end += length
03777 if python3:
03778 _v236.id = str[start:end].decode('utf-8')
03779 else:
03780 _v236.id = str[start:end]
03781 start = end
03782 end += 4
03783 (_v236.padding,) = _struct_f.unpack(str[start:end])
03784 _v239 = _v236.operation
03785 start = end
03786 end += 1
03787 (_v239.operation,) = _struct_b.unpack(str[start:end])
03788 start = end
03789 end += 4
03790 (length,) = _struct_I.unpack(str[start:end])
03791 _v236.shapes = []
03792 for i in range(0, length):
03793 val3 = arm_navigation_msgs.msg.Shape()
03794 start = end
03795 end += 1
03796 (val3.type,) = _struct_b.unpack(str[start:end])
03797 start = end
03798 end += 4
03799 (length,) = _struct_I.unpack(str[start:end])
03800 pattern = '<%sd'%length
03801 start = end
03802 end += struct.calcsize(pattern)
03803 val3.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03804 start = end
03805 end += 4
03806 (length,) = _struct_I.unpack(str[start:end])
03807 pattern = '<%si'%length
03808 start = end
03809 end += struct.calcsize(pattern)
03810 val3.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03811 start = end
03812 end += 4
03813 (length,) = _struct_I.unpack(str[start:end])
03814 val3.vertices = []
03815 for i in range(0, length):
03816 val4 = geometry_msgs.msg.Point()
03817 _x = val4
03818 start = end
03819 end += 24
03820 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03821 val3.vertices.append(val4)
03822 _v236.shapes.append(val3)
03823 start = end
03824 end += 4
03825 (length,) = _struct_I.unpack(str[start:end])
03826 _v236.poses = []
03827 for i in range(0, length):
03828 val3 = geometry_msgs.msg.Pose()
03829 _v240 = val3.position
03830 _x = _v240
03831 start = end
03832 end += 24
03833 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03834 _v241 = val3.orientation
03835 _x = _v241
03836 start = end
03837 end += 32
03838 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03839 _v236.poses.append(val3)
03840 start = end
03841 end += 4
03842 (length,) = _struct_I.unpack(str[start:end])
03843 val1.touch_links = []
03844 for i in range(0, length):
03845 start = end
03846 end += 4
03847 (length,) = _struct_I.unpack(str[start:end])
03848 start = end
03849 end += length
03850 if python3:
03851 val2 = str[start:end].decode('utf-8')
03852 else:
03853 val2 = str[start:end]
03854 val1.touch_links.append(val2)
03855 self.goal.planning_scene_diff.attached_collision_objects.append(val1)
03856 _x = self
03857 start = end
03858 end += 12
03859 (_x.goal.planning_scene_diff.collision_map.header.seq, _x.goal.planning_scene_diff.collision_map.header.stamp.secs, _x.goal.planning_scene_diff.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03860 start = end
03861 end += 4
03862 (length,) = _struct_I.unpack(str[start:end])
03863 start = end
03864 end += length
03865 if python3:
03866 self.goal.planning_scene_diff.collision_map.header.frame_id = str[start:end].decode('utf-8')
03867 else:
03868 self.goal.planning_scene_diff.collision_map.header.frame_id = str[start:end]
03869 start = end
03870 end += 4
03871 (length,) = _struct_I.unpack(str[start:end])
03872 self.goal.planning_scene_diff.collision_map.boxes = []
03873 for i in range(0, length):
03874 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
03875 _v242 = val1.center
03876 _x = _v242
03877 start = end
03878 end += 12
03879 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03880 _v243 = val1.extents
03881 _x = _v243
03882 start = end
03883 end += 12
03884 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03885 _v244 = val1.axis
03886 _x = _v244
03887 start = end
03888 end += 12
03889 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03890 start = end
03891 end += 4
03892 (val1.angle,) = _struct_f.unpack(str[start:end])
03893 self.goal.planning_scene_diff.collision_map.boxes.append(val1)
03894 start = end
03895 end += 1
03896 (self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.type,) = _struct_b.unpack(str[start:end])
03897 start = end
03898 end += 4
03899 (length,) = _struct_I.unpack(str[start:end])
03900 pattern = '<%sd'%length
03901 start = end
03902 end += struct.calcsize(pattern)
03903 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03904 start = end
03905 end += 4
03906 (length,) = _struct_I.unpack(str[start:end])
03907 pattern = '<%si'%length
03908 start = end
03909 end += struct.calcsize(pattern)
03910 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
03911 start = end
03912 end += 4
03913 (length,) = _struct_I.unpack(str[start:end])
03914 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices = []
03915 for i in range(0, length):
03916 val1 = geometry_msgs.msg.Point()
03917 _x = val1
03918 start = end
03919 end += 24
03920 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03921 self.goal.motion_plan_request.workspace_parameters.workspace_region_shape.vertices.append(val1)
03922 _x = self
03923 start = end
03924 end += 12
03925 (_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03926 start = end
03927 end += 4
03928 (length,) = _struct_I.unpack(str[start:end])
03929 start = end
03930 end += length
03931 if python3:
03932 self.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end].decode('utf-8')
03933 else:
03934 self.goal.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
03935 _x = self
03936 start = end
03937 end += 68
03938 (_x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.goal.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.goal.motion_plan_request.start_state.joint_state.header.seq, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.goal.motion_plan_request.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
03939 start = end
03940 end += 4
03941 (length,) = _struct_I.unpack(str[start:end])
03942 start = end
03943 end += length
03944 if python3:
03945 self.goal.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
03946 else:
03947 self.goal.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end]
03948 start = end
03949 end += 4
03950 (length,) = _struct_I.unpack(str[start:end])
03951 self.goal.motion_plan_request.start_state.joint_state.name = []
03952 for i in range(0, length):
03953 start = end
03954 end += 4
03955 (length,) = _struct_I.unpack(str[start:end])
03956 start = end
03957 end += length
03958 if python3:
03959 val1 = str[start:end].decode('utf-8')
03960 else:
03961 val1 = str[start:end]
03962 self.goal.motion_plan_request.start_state.joint_state.name.append(val1)
03963 start = end
03964 end += 4
03965 (length,) = _struct_I.unpack(str[start:end])
03966 pattern = '<%sd'%length
03967 start = end
03968 end += struct.calcsize(pattern)
03969 self.goal.motion_plan_request.start_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03970 start = end
03971 end += 4
03972 (length,) = _struct_I.unpack(str[start:end])
03973 pattern = '<%sd'%length
03974 start = end
03975 end += struct.calcsize(pattern)
03976 self.goal.motion_plan_request.start_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03977 start = end
03978 end += 4
03979 (length,) = _struct_I.unpack(str[start:end])
03980 pattern = '<%sd'%length
03981 start = end
03982 end += struct.calcsize(pattern)
03983 self.goal.motion_plan_request.start_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03984 _x = self
03985 start = end
03986 end += 8
03987 (_x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.goal.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03988 start = end
03989 end += 4
03990 (length,) = _struct_I.unpack(str[start:end])
03991 self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names = []
03992 for i in range(0, length):
03993 start = end
03994 end += 4
03995 (length,) = _struct_I.unpack(str[start:end])
03996 start = end
03997 end += length
03998 if python3:
03999 val1 = str[start:end].decode('utf-8')
04000 else:
04001 val1 = str[start:end]
04002 self.goal.motion_plan_request.start_state.multi_dof_joint_state.joint_names.append(val1)
04003 start = end
04004 end += 4
04005 (length,) = _struct_I.unpack(str[start:end])
04006 self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = []
04007 for i in range(0, length):
04008 start = end
04009 end += 4
04010 (length,) = _struct_I.unpack(str[start:end])
04011 start = end
04012 end += length
04013 if python3:
04014 val1 = str[start:end].decode('utf-8')
04015 else:
04016 val1 = str[start:end]
04017 self.goal.motion_plan_request.start_state.multi_dof_joint_state.frame_ids.append(val1)
04018 start = end
04019 end += 4
04020 (length,) = _struct_I.unpack(str[start:end])
04021 self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = []
04022 for i in range(0, length):
04023 start = end
04024 end += 4
04025 (length,) = _struct_I.unpack(str[start:end])
04026 start = end
04027 end += length
04028 if python3:
04029 val1 = str[start:end].decode('utf-8')
04030 else:
04031 val1 = str[start:end]
04032 self.goal.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
04033 start = end
04034 end += 4
04035 (length,) = _struct_I.unpack(str[start:end])
04036 self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses = []
04037 for i in range(0, length):
04038 val1 = geometry_msgs.msg.Pose()
04039 _v245 = val1.position
04040 _x = _v245
04041 start = end
04042 end += 24
04043 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04044 _v246 = val1.orientation
04045 _x = _v246
04046 start = end
04047 end += 32
04048 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04049 self.goal.motion_plan_request.start_state.multi_dof_joint_state.poses.append(val1)
04050 start = end
04051 end += 4
04052 (length,) = _struct_I.unpack(str[start:end])
04053 self.goal.motion_plan_request.goal_constraints.joint_constraints = []
04054 for i in range(0, length):
04055 val1 = arm_navigation_msgs.msg.JointConstraint()
04056 start = end
04057 end += 4
04058 (length,) = _struct_I.unpack(str[start:end])
04059 start = end
04060 end += length
04061 if python3:
04062 val1.joint_name = str[start:end].decode('utf-8')
04063 else:
04064 val1.joint_name = str[start:end]
04065 _x = val1
04066 start = end
04067 end += 32
04068 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
04069 self.goal.motion_plan_request.goal_constraints.joint_constraints.append(val1)
04070 start = end
04071 end += 4
04072 (length,) = _struct_I.unpack(str[start:end])
04073 self.goal.motion_plan_request.goal_constraints.position_constraints = []
04074 for i in range(0, length):
04075 val1 = arm_navigation_msgs.msg.PositionConstraint()
04076 _v247 = val1.header
04077 start = end
04078 end += 4
04079 (_v247.seq,) = _struct_I.unpack(str[start:end])
04080 _v248 = _v247.stamp
04081 _x = _v248
04082 start = end
04083 end += 8
04084 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04085 start = end
04086 end += 4
04087 (length,) = _struct_I.unpack(str[start:end])
04088 start = end
04089 end += length
04090 if python3:
04091 _v247.frame_id = str[start:end].decode('utf-8')
04092 else:
04093 _v247.frame_id = str[start:end]
04094 start = end
04095 end += 4
04096 (length,) = _struct_I.unpack(str[start:end])
04097 start = end
04098 end += length
04099 if python3:
04100 val1.link_name = str[start:end].decode('utf-8')
04101 else:
04102 val1.link_name = str[start:end]
04103 _v249 = val1.target_point_offset
04104 _x = _v249
04105 start = end
04106 end += 24
04107 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04108 _v250 = val1.position
04109 _x = _v250
04110 start = end
04111 end += 24
04112 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04113 _v251 = val1.constraint_region_shape
04114 start = end
04115 end += 1
04116 (_v251.type,) = _struct_b.unpack(str[start:end])
04117 start = end
04118 end += 4
04119 (length,) = _struct_I.unpack(str[start:end])
04120 pattern = '<%sd'%length
04121 start = end
04122 end += struct.calcsize(pattern)
04123 _v251.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04124 start = end
04125 end += 4
04126 (length,) = _struct_I.unpack(str[start:end])
04127 pattern = '<%si'%length
04128 start = end
04129 end += struct.calcsize(pattern)
04130 _v251.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04131 start = end
04132 end += 4
04133 (length,) = _struct_I.unpack(str[start:end])
04134 _v251.vertices = []
04135 for i in range(0, length):
04136 val3 = geometry_msgs.msg.Point()
04137 _x = val3
04138 start = end
04139 end += 24
04140 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04141 _v251.vertices.append(val3)
04142 _v252 = val1.constraint_region_orientation
04143 _x = _v252
04144 start = end
04145 end += 32
04146 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04147 start = end
04148 end += 8
04149 (val1.weight,) = _struct_d.unpack(str[start:end])
04150 self.goal.motion_plan_request.goal_constraints.position_constraints.append(val1)
04151 start = end
04152 end += 4
04153 (length,) = _struct_I.unpack(str[start:end])
04154 self.goal.motion_plan_request.goal_constraints.orientation_constraints = []
04155 for i in range(0, length):
04156 val1 = arm_navigation_msgs.msg.OrientationConstraint()
04157 _v253 = val1.header
04158 start = end
04159 end += 4
04160 (_v253.seq,) = _struct_I.unpack(str[start:end])
04161 _v254 = _v253.stamp
04162 _x = _v254
04163 start = end
04164 end += 8
04165 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04166 start = end
04167 end += 4
04168 (length,) = _struct_I.unpack(str[start:end])
04169 start = end
04170 end += length
04171 if python3:
04172 _v253.frame_id = str[start:end].decode('utf-8')
04173 else:
04174 _v253.frame_id = str[start:end]
04175 start = end
04176 end += 4
04177 (length,) = _struct_I.unpack(str[start:end])
04178 start = end
04179 end += length
04180 if python3:
04181 val1.link_name = str[start:end].decode('utf-8')
04182 else:
04183 val1.link_name = str[start:end]
04184 start = end
04185 end += 4
04186 (val1.type,) = _struct_i.unpack(str[start:end])
04187 _v255 = val1.orientation
04188 _x = _v255
04189 start = end
04190 end += 32
04191 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04192 _x = val1
04193 start = end
04194 end += 32
04195 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
04196 self.goal.motion_plan_request.goal_constraints.orientation_constraints.append(val1)
04197 start = end
04198 end += 4
04199 (length,) = _struct_I.unpack(str[start:end])
04200 self.goal.motion_plan_request.goal_constraints.visibility_constraints = []
04201 for i in range(0, length):
04202 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
04203 _v256 = val1.header
04204 start = end
04205 end += 4
04206 (_v256.seq,) = _struct_I.unpack(str[start:end])
04207 _v257 = _v256.stamp
04208 _x = _v257
04209 start = end
04210 end += 8
04211 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04212 start = end
04213 end += 4
04214 (length,) = _struct_I.unpack(str[start:end])
04215 start = end
04216 end += length
04217 if python3:
04218 _v256.frame_id = str[start:end].decode('utf-8')
04219 else:
04220 _v256.frame_id = str[start:end]
04221 _v258 = val1.target
04222 _v259 = _v258.header
04223 start = end
04224 end += 4
04225 (_v259.seq,) = _struct_I.unpack(str[start:end])
04226 _v260 = _v259.stamp
04227 _x = _v260
04228 start = end
04229 end += 8
04230 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04231 start = end
04232 end += 4
04233 (length,) = _struct_I.unpack(str[start:end])
04234 start = end
04235 end += length
04236 if python3:
04237 _v259.frame_id = str[start:end].decode('utf-8')
04238 else:
04239 _v259.frame_id = str[start:end]
04240 _v261 = _v258.point
04241 _x = _v261
04242 start = end
04243 end += 24
04244 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04245 _v262 = val1.sensor_pose
04246 _v263 = _v262.header
04247 start = end
04248 end += 4
04249 (_v263.seq,) = _struct_I.unpack(str[start:end])
04250 _v264 = _v263.stamp
04251 _x = _v264
04252 start = end
04253 end += 8
04254 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04255 start = end
04256 end += 4
04257 (length,) = _struct_I.unpack(str[start:end])
04258 start = end
04259 end += length
04260 if python3:
04261 _v263.frame_id = str[start:end].decode('utf-8')
04262 else:
04263 _v263.frame_id = str[start:end]
04264 _v265 = _v262.pose
04265 _v266 = _v265.position
04266 _x = _v266
04267 start = end
04268 end += 24
04269 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04270 _v267 = _v265.orientation
04271 _x = _v267
04272 start = end
04273 end += 32
04274 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04275 start = end
04276 end += 8
04277 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
04278 self.goal.motion_plan_request.goal_constraints.visibility_constraints.append(val1)
04279 start = end
04280 end += 4
04281 (length,) = _struct_I.unpack(str[start:end])
04282 self.goal.motion_plan_request.path_constraints.joint_constraints = []
04283 for i in range(0, length):
04284 val1 = arm_navigation_msgs.msg.JointConstraint()
04285 start = end
04286 end += 4
04287 (length,) = _struct_I.unpack(str[start:end])
04288 start = end
04289 end += length
04290 if python3:
04291 val1.joint_name = str[start:end].decode('utf-8')
04292 else:
04293 val1.joint_name = str[start:end]
04294 _x = val1
04295 start = end
04296 end += 32
04297 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
04298 self.goal.motion_plan_request.path_constraints.joint_constraints.append(val1)
04299 start = end
04300 end += 4
04301 (length,) = _struct_I.unpack(str[start:end])
04302 self.goal.motion_plan_request.path_constraints.position_constraints = []
04303 for i in range(0, length):
04304 val1 = arm_navigation_msgs.msg.PositionConstraint()
04305 _v268 = val1.header
04306 start = end
04307 end += 4
04308 (_v268.seq,) = _struct_I.unpack(str[start:end])
04309 _v269 = _v268.stamp
04310 _x = _v269
04311 start = end
04312 end += 8
04313 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04314 start = end
04315 end += 4
04316 (length,) = _struct_I.unpack(str[start:end])
04317 start = end
04318 end += length
04319 if python3:
04320 _v268.frame_id = str[start:end].decode('utf-8')
04321 else:
04322 _v268.frame_id = str[start:end]
04323 start = end
04324 end += 4
04325 (length,) = _struct_I.unpack(str[start:end])
04326 start = end
04327 end += length
04328 if python3:
04329 val1.link_name = str[start:end].decode('utf-8')
04330 else:
04331 val1.link_name = str[start:end]
04332 _v270 = val1.target_point_offset
04333 _x = _v270
04334 start = end
04335 end += 24
04336 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04337 _v271 = val1.position
04338 _x = _v271
04339 start = end
04340 end += 24
04341 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04342 _v272 = val1.constraint_region_shape
04343 start = end
04344 end += 1
04345 (_v272.type,) = _struct_b.unpack(str[start:end])
04346 start = end
04347 end += 4
04348 (length,) = _struct_I.unpack(str[start:end])
04349 pattern = '<%sd'%length
04350 start = end
04351 end += struct.calcsize(pattern)
04352 _v272.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04353 start = end
04354 end += 4
04355 (length,) = _struct_I.unpack(str[start:end])
04356 pattern = '<%si'%length
04357 start = end
04358 end += struct.calcsize(pattern)
04359 _v272.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04360 start = end
04361 end += 4
04362 (length,) = _struct_I.unpack(str[start:end])
04363 _v272.vertices = []
04364 for i in range(0, length):
04365 val3 = geometry_msgs.msg.Point()
04366 _x = val3
04367 start = end
04368 end += 24
04369 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04370 _v272.vertices.append(val3)
04371 _v273 = val1.constraint_region_orientation
04372 _x = _v273
04373 start = end
04374 end += 32
04375 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04376 start = end
04377 end += 8
04378 (val1.weight,) = _struct_d.unpack(str[start:end])
04379 self.goal.motion_plan_request.path_constraints.position_constraints.append(val1)
04380 start = end
04381 end += 4
04382 (length,) = _struct_I.unpack(str[start:end])
04383 self.goal.motion_plan_request.path_constraints.orientation_constraints = []
04384 for i in range(0, length):
04385 val1 = arm_navigation_msgs.msg.OrientationConstraint()
04386 _v274 = val1.header
04387 start = end
04388 end += 4
04389 (_v274.seq,) = _struct_I.unpack(str[start:end])
04390 _v275 = _v274.stamp
04391 _x = _v275
04392 start = end
04393 end += 8
04394 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04395 start = end
04396 end += 4
04397 (length,) = _struct_I.unpack(str[start:end])
04398 start = end
04399 end += length
04400 if python3:
04401 _v274.frame_id = str[start:end].decode('utf-8')
04402 else:
04403 _v274.frame_id = str[start:end]
04404 start = end
04405 end += 4
04406 (length,) = _struct_I.unpack(str[start:end])
04407 start = end
04408 end += length
04409 if python3:
04410 val1.link_name = str[start:end].decode('utf-8')
04411 else:
04412 val1.link_name = str[start:end]
04413 start = end
04414 end += 4
04415 (val1.type,) = _struct_i.unpack(str[start:end])
04416 _v276 = val1.orientation
04417 _x = _v276
04418 start = end
04419 end += 32
04420 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04421 _x = val1
04422 start = end
04423 end += 32
04424 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
04425 self.goal.motion_plan_request.path_constraints.orientation_constraints.append(val1)
04426 start = end
04427 end += 4
04428 (length,) = _struct_I.unpack(str[start:end])
04429 self.goal.motion_plan_request.path_constraints.visibility_constraints = []
04430 for i in range(0, length):
04431 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
04432 _v277 = val1.header
04433 start = end
04434 end += 4
04435 (_v277.seq,) = _struct_I.unpack(str[start:end])
04436 _v278 = _v277.stamp
04437 _x = _v278
04438 start = end
04439 end += 8
04440 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04441 start = end
04442 end += 4
04443 (length,) = _struct_I.unpack(str[start:end])
04444 start = end
04445 end += length
04446 if python3:
04447 _v277.frame_id = str[start:end].decode('utf-8')
04448 else:
04449 _v277.frame_id = str[start:end]
04450 _v279 = val1.target
04451 _v280 = _v279.header
04452 start = end
04453 end += 4
04454 (_v280.seq,) = _struct_I.unpack(str[start:end])
04455 _v281 = _v280.stamp
04456 _x = _v281
04457 start = end
04458 end += 8
04459 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04460 start = end
04461 end += 4
04462 (length,) = _struct_I.unpack(str[start:end])
04463 start = end
04464 end += length
04465 if python3:
04466 _v280.frame_id = str[start:end].decode('utf-8')
04467 else:
04468 _v280.frame_id = str[start:end]
04469 _v282 = _v279.point
04470 _x = _v282
04471 start = end
04472 end += 24
04473 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04474 _v283 = val1.sensor_pose
04475 _v284 = _v283.header
04476 start = end
04477 end += 4
04478 (_v284.seq,) = _struct_I.unpack(str[start:end])
04479 _v285 = _v284.stamp
04480 _x = _v285
04481 start = end
04482 end += 8
04483 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04484 start = end
04485 end += 4
04486 (length,) = _struct_I.unpack(str[start:end])
04487 start = end
04488 end += length
04489 if python3:
04490 _v284.frame_id = str[start:end].decode('utf-8')
04491 else:
04492 _v284.frame_id = str[start:end]
04493 _v286 = _v283.pose
04494 _v287 = _v286.position
04495 _x = _v287
04496 start = end
04497 end += 24
04498 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04499 _v288 = _v286.orientation
04500 _x = _v288
04501 start = end
04502 end += 32
04503 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04504 start = end
04505 end += 8
04506 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
04507 self.goal.motion_plan_request.path_constraints.visibility_constraints.append(val1)
04508 start = end
04509 end += 4
04510 (length,) = _struct_I.unpack(str[start:end])
04511 start = end
04512 end += length
04513 if python3:
04514 self.goal.motion_plan_request.planner_id = str[start:end].decode('utf-8')
04515 else:
04516 self.goal.motion_plan_request.planner_id = str[start:end]
04517 start = end
04518 end += 4
04519 (length,) = _struct_I.unpack(str[start:end])
04520 start = end
04521 end += length
04522 if python3:
04523 self.goal.motion_plan_request.group_name = str[start:end].decode('utf-8')
04524 else:
04525 self.goal.motion_plan_request.group_name = str[start:end]
04526 _x = self
04527 start = end
04528 end += 28
04529 (_x.goal.motion_plan_request.num_planning_attempts, _x.goal.motion_plan_request.allowed_planning_time.secs, _x.goal.motion_plan_request.allowed_planning_time.nsecs, _x.goal.motion_plan_request.expected_path_duration.secs, _x.goal.motion_plan_request.expected_path_duration.nsecs, _x.goal.motion_plan_request.expected_path_dt.secs, _x.goal.motion_plan_request.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
04530 start = end
04531 end += 4
04532 (length,) = _struct_I.unpack(str[start:end])
04533 self.goal.operations.collision_operations = []
04534 for i in range(0, length):
04535 val1 = arm_navigation_msgs.msg.CollisionOperation()
04536 start = end
04537 end += 4
04538 (length,) = _struct_I.unpack(str[start:end])
04539 start = end
04540 end += length
04541 if python3:
04542 val1.object1 = str[start:end].decode('utf-8')
04543 else:
04544 val1.object1 = str[start:end]
04545 start = end
04546 end += 4
04547 (length,) = _struct_I.unpack(str[start:end])
04548 start = end
04549 end += length
04550 if python3:
04551 val1.object2 = str[start:end].decode('utf-8')
04552 else:
04553 val1.object2 = str[start:end]
04554 _x = val1
04555 start = end
04556 end += 12
04557 (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
04558 self.goal.operations.collision_operations.append(val1)
04559 _x = self
04560 start = end
04561 end += 4
04562 (_x.goal.accept_partial_plans, _x.goal.accept_invalid_goals, _x.goal.disable_ik, _x.goal.disable_collision_monitoring,) = _struct_4B.unpack(str[start:end])
04563 self.goal.accept_partial_plans = bool(self.goal.accept_partial_plans)
04564 self.goal.accept_invalid_goals = bool(self.goal.accept_invalid_goals)
04565 self.goal.disable_ik = bool(self.goal.disable_ik)
04566 self.goal.disable_collision_monitoring = bool(self.goal.disable_collision_monitoring)
04567 return self
04568 except struct.error as e:
04569 raise genpy.DeserializationError(e)
04570
04571 _struct_I = genpy.struct_I
04572 _struct_7d3I = struct.Struct("<7d3I")
04573 _struct_b = struct.Struct("<b")
04574 _struct_d = struct.Struct("<d")
04575 _struct_f = struct.Struct("<f")
04576 _struct_di = struct.Struct("<di")
04577 _struct_7i = struct.Struct("<7i")
04578 _struct_3f = struct.Struct("<3f")
04579 _struct_i = struct.Struct("<i")
04580 _struct_3I = struct.Struct("<3I")
04581 _struct_4d = struct.Struct("<4d")
04582 _struct_4B = struct.Struct("<4B")
04583 _struct_2I = struct.Struct("<2I")
04584 _struct_3d = struct.Struct("<3d")