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


arm_navigation_msgs
Author(s): Gil Jones
autogenerated on Thu Dec 12 2013 11:08:10