00001 """autogenerated by genpy from arm_navigation_msgs/GetMotionPlanRequest.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 GetMotionPlanRequest(genpy.Message):
00014 _md5sum = "53194db8d1959c06cb41e066f1f6695e"
00015 _type = "arm_navigation_msgs/GetMotionPlanRequest"
00016 _has_header = False
00017 _full_text = """
00018
00019
00020 MotionPlanRequest motion_plan_request
00021
00022
00023 ================================================================================
00024 MSG: arm_navigation_msgs/MotionPlanRequest
00025 # This service contains the definition for a request to the motion
00026 # planner and the output it provides
00027
00028 # Parameters for the workspace that the planner should work inside
00029 arm_navigation_msgs/WorkspaceParameters workspace_parameters
00030
00031 # Starting state updates. If certain joints should be considered
00032 # at positions other than the current ones, these positions should
00033 # be set here
00034 arm_navigation_msgs/RobotState start_state
00035
00036 # The goal state for the model to plan for. The goal is achieved
00037 # if all constraints are satisfied
00038 arm_navigation_msgs/Constraints goal_constraints
00039
00040 # No state at any point along the path in the produced motion plan will violate these constraints
00041 arm_navigation_msgs/Constraints path_constraints
00042
00043 # The name of the motion planner to use. If no name is specified,
00044 # a default motion planner will be used
00045 string planner_id
00046
00047 # The name of the group of joints on which this planner is operating
00048 string group_name
00049
00050 # The number of times this plan is to be computed. Shortest solution
00051 # will be reported.
00052 int32 num_planning_attempts
00053
00054 # The maximum amount of time the motion planner is allowed to plan for
00055 duration allowed_planning_time
00056
00057 # 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
00058 duration expected_path_duration
00059 duration expected_path_dt
00060
00061 ================================================================================
00062 MSG: arm_navigation_msgs/WorkspaceParameters
00063 # This message contains a set of parameters useful in
00064 # setting up the workspace for planning
00065 arm_navigation_msgs/Shape workspace_region_shape
00066 geometry_msgs/PoseStamped workspace_region_pose
00067
00068
00069 ================================================================================
00070 MSG: arm_navigation_msgs/Shape
00071 byte SPHERE=0
00072 byte BOX=1
00073 byte CYLINDER=2
00074 byte MESH=3
00075
00076 byte type
00077
00078
00079 #### define sphere, box, cylinder ####
00080 # the origin of each shape is considered at the shape's center
00081
00082 # for sphere
00083 # radius := dimensions[0]
00084
00085 # for cylinder
00086 # radius := dimensions[0]
00087 # length := dimensions[1]
00088 # the length is along the Z axis
00089
00090 # for box
00091 # size_x := dimensions[0]
00092 # size_y := dimensions[1]
00093 # size_z := dimensions[2]
00094 float64[] dimensions
00095
00096
00097 #### define mesh ####
00098
00099 # list of triangles; triangle k is defined by tre vertices located
00100 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00101 int32[] triangles
00102 geometry_msgs/Point[] vertices
00103
00104 ================================================================================
00105 MSG: geometry_msgs/Point
00106 # This contains the position of a point in free space
00107 float64 x
00108 float64 y
00109 float64 z
00110
00111 ================================================================================
00112 MSG: geometry_msgs/PoseStamped
00113 # A Pose with reference coordinate frame and timestamp
00114 Header header
00115 Pose pose
00116
00117 ================================================================================
00118 MSG: std_msgs/Header
00119 # Standard metadata for higher-level stamped data types.
00120 # This is generally used to communicate timestamped data
00121 # in a particular coordinate frame.
00122 #
00123 # sequence ID: consecutively increasing ID
00124 uint32 seq
00125 #Two-integer timestamp that is expressed as:
00126 # * stamp.secs: seconds (stamp_secs) since epoch
00127 # * stamp.nsecs: nanoseconds since stamp_secs
00128 # time-handling sugar is provided by the client library
00129 time stamp
00130 #Frame this data is associated with
00131 # 0: no frame
00132 # 1: global frame
00133 string frame_id
00134
00135 ================================================================================
00136 MSG: geometry_msgs/Pose
00137 # A representation of pose in free space, composed of postion and orientation.
00138 Point position
00139 Quaternion orientation
00140
00141 ================================================================================
00142 MSG: geometry_msgs/Quaternion
00143 # This represents an orientation in free space in quaternion form.
00144
00145 float64 x
00146 float64 y
00147 float64 z
00148 float64 w
00149
00150 ================================================================================
00151 MSG: arm_navigation_msgs/RobotState
00152 # This message contains information about the robot state, i.e. the positions of its joints and links
00153 sensor_msgs/JointState joint_state
00154 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00155
00156 ================================================================================
00157 MSG: sensor_msgs/JointState
00158 # This is a message that holds data to describe the state of a set of torque controlled joints.
00159 #
00160 # The state of each joint (revolute or prismatic) is defined by:
00161 # * the position of the joint (rad or m),
00162 # * the velocity of the joint (rad/s or m/s) and
00163 # * the effort that is applied in the joint (Nm or N).
00164 #
00165 # Each joint is uniquely identified by its name
00166 # The header specifies the time at which the joint states were recorded. All the joint states
00167 # in one message have to be recorded at the same time.
00168 #
00169 # This message consists of a multiple arrays, one for each part of the joint state.
00170 # The goal is to make each of the fields optional. When e.g. your joints have no
00171 # effort associated with them, you can leave the effort array empty.
00172 #
00173 # All arrays in this message should have the same size, or be empty.
00174 # This is the only way to uniquely associate the joint name with the correct
00175 # states.
00176
00177
00178 Header header
00179
00180 string[] name
00181 float64[] position
00182 float64[] velocity
00183 float64[] effort
00184
00185 ================================================================================
00186 MSG: arm_navigation_msgs/MultiDOFJointState
00187 #A representation of a multi-dof joint state
00188 time stamp
00189 string[] joint_names
00190 string[] frame_ids
00191 string[] child_frame_ids
00192 geometry_msgs/Pose[] poses
00193
00194 ================================================================================
00195 MSG: arm_navigation_msgs/Constraints
00196 # This message contains a list of motion planning constraints.
00197
00198 arm_navigation_msgs/JointConstraint[] joint_constraints
00199 arm_navigation_msgs/PositionConstraint[] position_constraints
00200 arm_navigation_msgs/OrientationConstraint[] orientation_constraints
00201 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints
00202
00203 ================================================================================
00204 MSG: arm_navigation_msgs/JointConstraint
00205 # Constrain the position of a joint to be within a certain bound
00206 string joint_name
00207
00208 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00209 float64 position
00210 float64 tolerance_above
00211 float64 tolerance_below
00212
00213 # A weighting factor for this constraint
00214 float64 weight
00215 ================================================================================
00216 MSG: arm_navigation_msgs/PositionConstraint
00217 # This message contains the definition of a position constraint.
00218 Header header
00219
00220 # The robot link this constraint refers to
00221 string link_name
00222
00223 # The offset (in the link frame) for the target point on the link we are planning for
00224 geometry_msgs/Point target_point_offset
00225
00226 # The nominal/target position for the point we are planning for
00227 geometry_msgs/Point position
00228
00229 # The shape of the bounded region that constrains the position of the end-effector
00230 # This region is always centered at the position defined above
00231 arm_navigation_msgs/Shape constraint_region_shape
00232
00233 # The orientation of the bounded region that constrains the position of the end-effector.
00234 # This allows the specification of non-axis aligned constraints
00235 geometry_msgs/Quaternion constraint_region_orientation
00236
00237 # Constraint weighting factor - a weight for this constraint
00238 float64 weight
00239
00240 ================================================================================
00241 MSG: arm_navigation_msgs/OrientationConstraint
00242 # This message contains the definition of an orientation constraint.
00243 Header header
00244
00245 # The robot link this constraint refers to
00246 string link_name
00247
00248 # The type of the constraint
00249 int32 type
00250 int32 LINK_FRAME=0
00251 int32 HEADER_FRAME=1
00252
00253 # The desired orientation of the robot link specified as a quaternion
00254 geometry_msgs/Quaternion orientation
00255
00256 # optional RPY error tolerances specified if
00257 float64 absolute_roll_tolerance
00258 float64 absolute_pitch_tolerance
00259 float64 absolute_yaw_tolerance
00260
00261 # Constraint weighting factor - a weight for this constraint
00262 float64 weight
00263
00264 ================================================================================
00265 MSG: arm_navigation_msgs/VisibilityConstraint
00266 # This message contains the definition of a visibility constraint.
00267 Header header
00268
00269 # The point stamped target that needs to be kept within view of the sensor
00270 geometry_msgs/PointStamped target
00271
00272 # The local pose of the frame in which visibility is to be maintained
00273 # The frame id should represent the robot link to which the sensor is attached
00274 # The visual axis of the sensor is assumed to be along the X axis of this frame
00275 geometry_msgs/PoseStamped sensor_pose
00276
00277 # The deviation (in radians) that will be tolerated
00278 # Constraint error will be measured as the solid angle between the
00279 # X axis of the frame defined above and the vector between the origin
00280 # of the frame defined above and the target location
00281 float64 absolute_tolerance
00282
00283
00284 ================================================================================
00285 MSG: geometry_msgs/PointStamped
00286 # This represents a Point with reference coordinate frame and timestamp
00287 Header header
00288 Point point
00289
00290 """
00291 __slots__ = ['motion_plan_request']
00292 _slot_types = ['arm_navigation_msgs/MotionPlanRequest']
00293
00294 def __init__(self, *args, **kwds):
00295 """
00296 Constructor. Any message fields that are implicitly/explicitly
00297 set to None will be assigned a default value. The recommend
00298 use is keyword arguments as this is more robust to future message
00299 changes. You cannot mix in-order arguments and keyword arguments.
00300
00301 The available fields are:
00302 motion_plan_request
00303
00304 :param args: complete set of field values, in .msg order
00305 :param kwds: use keyword arguments corresponding to message field names
00306 to set specific fields.
00307 """
00308 if args or kwds:
00309 super(GetMotionPlanRequest, self).__init__(*args, **kwds)
00310
00311 if self.motion_plan_request is None:
00312 self.motion_plan_request = arm_navigation_msgs.msg.MotionPlanRequest()
00313 else:
00314 self.motion_plan_request = arm_navigation_msgs.msg.MotionPlanRequest()
00315
00316 def _get_types(self):
00317 """
00318 internal API method
00319 """
00320 return self._slot_types
00321
00322 def serialize(self, buff):
00323 """
00324 serialize message into buffer
00325 :param buff: buffer, ``StringIO``
00326 """
00327 try:
00328 buff.write(_struct_b.pack(self.motion_plan_request.workspace_parameters.workspace_region_shape.type))
00329 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions)
00330 buff.write(_struct_I.pack(length))
00331 pattern = '<%sd'%length
00332 buff.write(struct.pack(pattern, *self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions))
00333 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles)
00334 buff.write(_struct_I.pack(length))
00335 pattern = '<%si'%length
00336 buff.write(struct.pack(pattern, *self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles))
00337 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices)
00338 buff.write(_struct_I.pack(length))
00339 for val1 in self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices:
00340 _x = val1
00341 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00342 _x = self
00343 buff.write(_struct_3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
00344 _x = self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id
00345 length = len(_x)
00346 if python3 or type(_x) == unicode:
00347 _x = _x.encode('utf-8')
00348 length = len(_x)
00349 buff.write(struct.pack('<I%ss'%length, length, _x))
00350 _x = self
00351 buff.write(_struct_7d3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs))
00352 _x = self.motion_plan_request.start_state.joint_state.header.frame_id
00353 length = len(_x)
00354 if python3 or type(_x) == unicode:
00355 _x = _x.encode('utf-8')
00356 length = len(_x)
00357 buff.write(struct.pack('<I%ss'%length, length, _x))
00358 length = len(self.motion_plan_request.start_state.joint_state.name)
00359 buff.write(_struct_I.pack(length))
00360 for val1 in self.motion_plan_request.start_state.joint_state.name:
00361 length = len(val1)
00362 if python3 or type(val1) == unicode:
00363 val1 = val1.encode('utf-8')
00364 length = len(val1)
00365 buff.write(struct.pack('<I%ss'%length, length, val1))
00366 length = len(self.motion_plan_request.start_state.joint_state.position)
00367 buff.write(_struct_I.pack(length))
00368 pattern = '<%sd'%length
00369 buff.write(struct.pack(pattern, *self.motion_plan_request.start_state.joint_state.position))
00370 length = len(self.motion_plan_request.start_state.joint_state.velocity)
00371 buff.write(_struct_I.pack(length))
00372 pattern = '<%sd'%length
00373 buff.write(struct.pack(pattern, *self.motion_plan_request.start_state.joint_state.velocity))
00374 length = len(self.motion_plan_request.start_state.joint_state.effort)
00375 buff.write(_struct_I.pack(length))
00376 pattern = '<%sd'%length
00377 buff.write(struct.pack(pattern, *self.motion_plan_request.start_state.joint_state.effort))
00378 _x = self
00379 buff.write(_struct_2I.pack(_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs))
00380 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.joint_names)
00381 buff.write(_struct_I.pack(length))
00382 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.joint_names:
00383 length = len(val1)
00384 if python3 or type(val1) == unicode:
00385 val1 = val1.encode('utf-8')
00386 length = len(val1)
00387 buff.write(struct.pack('<I%ss'%length, length, val1))
00388 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids)
00389 buff.write(_struct_I.pack(length))
00390 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids:
00391 length = len(val1)
00392 if python3 or type(val1) == unicode:
00393 val1 = val1.encode('utf-8')
00394 length = len(val1)
00395 buff.write(struct.pack('<I%ss'%length, length, val1))
00396 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids)
00397 buff.write(_struct_I.pack(length))
00398 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids:
00399 length = len(val1)
00400 if python3 or type(val1) == unicode:
00401 val1 = val1.encode('utf-8')
00402 length = len(val1)
00403 buff.write(struct.pack('<I%ss'%length, length, val1))
00404 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.poses)
00405 buff.write(_struct_I.pack(length))
00406 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.poses:
00407 _v1 = val1.position
00408 _x = _v1
00409 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00410 _v2 = val1.orientation
00411 _x = _v2
00412 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00413 length = len(self.motion_plan_request.goal_constraints.joint_constraints)
00414 buff.write(_struct_I.pack(length))
00415 for val1 in self.motion_plan_request.goal_constraints.joint_constraints:
00416 _x = val1.joint_name
00417 length = len(_x)
00418 if python3 or type(_x) == unicode:
00419 _x = _x.encode('utf-8')
00420 length = len(_x)
00421 buff.write(struct.pack('<I%ss'%length, length, _x))
00422 _x = val1
00423 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00424 length = len(self.motion_plan_request.goal_constraints.position_constraints)
00425 buff.write(_struct_I.pack(length))
00426 for val1 in self.motion_plan_request.goal_constraints.position_constraints:
00427 _v3 = val1.header
00428 buff.write(_struct_I.pack(_v3.seq))
00429 _v4 = _v3.stamp
00430 _x = _v4
00431 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00432 _x = _v3.frame_id
00433 length = len(_x)
00434 if python3 or type(_x) == unicode:
00435 _x = _x.encode('utf-8')
00436 length = len(_x)
00437 buff.write(struct.pack('<I%ss'%length, length, _x))
00438 _x = val1.link_name
00439 length = len(_x)
00440 if python3 or type(_x) == unicode:
00441 _x = _x.encode('utf-8')
00442 length = len(_x)
00443 buff.write(struct.pack('<I%ss'%length, length, _x))
00444 _v5 = val1.target_point_offset
00445 _x = _v5
00446 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00447 _v6 = val1.position
00448 _x = _v6
00449 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00450 _v7 = val1.constraint_region_shape
00451 buff.write(_struct_b.pack(_v7.type))
00452 length = len(_v7.dimensions)
00453 buff.write(_struct_I.pack(length))
00454 pattern = '<%sd'%length
00455 buff.write(struct.pack(pattern, *_v7.dimensions))
00456 length = len(_v7.triangles)
00457 buff.write(_struct_I.pack(length))
00458 pattern = '<%si'%length
00459 buff.write(struct.pack(pattern, *_v7.triangles))
00460 length = len(_v7.vertices)
00461 buff.write(_struct_I.pack(length))
00462 for val3 in _v7.vertices:
00463 _x = val3
00464 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00465 _v8 = val1.constraint_region_orientation
00466 _x = _v8
00467 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00468 buff.write(_struct_d.pack(val1.weight))
00469 length = len(self.motion_plan_request.goal_constraints.orientation_constraints)
00470 buff.write(_struct_I.pack(length))
00471 for val1 in self.motion_plan_request.goal_constraints.orientation_constraints:
00472 _v9 = val1.header
00473 buff.write(_struct_I.pack(_v9.seq))
00474 _v10 = _v9.stamp
00475 _x = _v10
00476 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00477 _x = _v9.frame_id
00478 length = len(_x)
00479 if python3 or type(_x) == unicode:
00480 _x = _x.encode('utf-8')
00481 length = len(_x)
00482 buff.write(struct.pack('<I%ss'%length, length, _x))
00483 _x = val1.link_name
00484 length = len(_x)
00485 if python3 or type(_x) == unicode:
00486 _x = _x.encode('utf-8')
00487 length = len(_x)
00488 buff.write(struct.pack('<I%ss'%length, length, _x))
00489 buff.write(_struct_i.pack(val1.type))
00490 _v11 = val1.orientation
00491 _x = _v11
00492 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00493 _x = val1
00494 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00495 length = len(self.motion_plan_request.goal_constraints.visibility_constraints)
00496 buff.write(_struct_I.pack(length))
00497 for val1 in self.motion_plan_request.goal_constraints.visibility_constraints:
00498 _v12 = val1.header
00499 buff.write(_struct_I.pack(_v12.seq))
00500 _v13 = _v12.stamp
00501 _x = _v13
00502 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00503 _x = _v12.frame_id
00504 length = len(_x)
00505 if python3 or type(_x) == unicode:
00506 _x = _x.encode('utf-8')
00507 length = len(_x)
00508 buff.write(struct.pack('<I%ss'%length, length, _x))
00509 _v14 = val1.target
00510 _v15 = _v14.header
00511 buff.write(_struct_I.pack(_v15.seq))
00512 _v16 = _v15.stamp
00513 _x = _v16
00514 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00515 _x = _v15.frame_id
00516 length = len(_x)
00517 if python3 or type(_x) == unicode:
00518 _x = _x.encode('utf-8')
00519 length = len(_x)
00520 buff.write(struct.pack('<I%ss'%length, length, _x))
00521 _v17 = _v14.point
00522 _x = _v17
00523 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00524 _v18 = val1.sensor_pose
00525 _v19 = _v18.header
00526 buff.write(_struct_I.pack(_v19.seq))
00527 _v20 = _v19.stamp
00528 _x = _v20
00529 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00530 _x = _v19.frame_id
00531 length = len(_x)
00532 if python3 or type(_x) == unicode:
00533 _x = _x.encode('utf-8')
00534 length = len(_x)
00535 buff.write(struct.pack('<I%ss'%length, length, _x))
00536 _v21 = _v18.pose
00537 _v22 = _v21.position
00538 _x = _v22
00539 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00540 _v23 = _v21.orientation
00541 _x = _v23
00542 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00543 buff.write(_struct_d.pack(val1.absolute_tolerance))
00544 length = len(self.motion_plan_request.path_constraints.joint_constraints)
00545 buff.write(_struct_I.pack(length))
00546 for val1 in self.motion_plan_request.path_constraints.joint_constraints:
00547 _x = val1.joint_name
00548 length = len(_x)
00549 if python3 or type(_x) == unicode:
00550 _x = _x.encode('utf-8')
00551 length = len(_x)
00552 buff.write(struct.pack('<I%ss'%length, length, _x))
00553 _x = val1
00554 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00555 length = len(self.motion_plan_request.path_constraints.position_constraints)
00556 buff.write(_struct_I.pack(length))
00557 for val1 in self.motion_plan_request.path_constraints.position_constraints:
00558 _v24 = val1.header
00559 buff.write(_struct_I.pack(_v24.seq))
00560 _v25 = _v24.stamp
00561 _x = _v25
00562 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00563 _x = _v24.frame_id
00564 length = len(_x)
00565 if python3 or type(_x) == unicode:
00566 _x = _x.encode('utf-8')
00567 length = len(_x)
00568 buff.write(struct.pack('<I%ss'%length, length, _x))
00569 _x = val1.link_name
00570 length = len(_x)
00571 if python3 or type(_x) == unicode:
00572 _x = _x.encode('utf-8')
00573 length = len(_x)
00574 buff.write(struct.pack('<I%ss'%length, length, _x))
00575 _v26 = val1.target_point_offset
00576 _x = _v26
00577 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00578 _v27 = val1.position
00579 _x = _v27
00580 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00581 _v28 = val1.constraint_region_shape
00582 buff.write(_struct_b.pack(_v28.type))
00583 length = len(_v28.dimensions)
00584 buff.write(_struct_I.pack(length))
00585 pattern = '<%sd'%length
00586 buff.write(struct.pack(pattern, *_v28.dimensions))
00587 length = len(_v28.triangles)
00588 buff.write(_struct_I.pack(length))
00589 pattern = '<%si'%length
00590 buff.write(struct.pack(pattern, *_v28.triangles))
00591 length = len(_v28.vertices)
00592 buff.write(_struct_I.pack(length))
00593 for val3 in _v28.vertices:
00594 _x = val3
00595 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00596 _v29 = val1.constraint_region_orientation
00597 _x = _v29
00598 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00599 buff.write(_struct_d.pack(val1.weight))
00600 length = len(self.motion_plan_request.path_constraints.orientation_constraints)
00601 buff.write(_struct_I.pack(length))
00602 for val1 in self.motion_plan_request.path_constraints.orientation_constraints:
00603 _v30 = val1.header
00604 buff.write(_struct_I.pack(_v30.seq))
00605 _v31 = _v30.stamp
00606 _x = _v31
00607 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00608 _x = _v30.frame_id
00609 length = len(_x)
00610 if python3 or type(_x) == unicode:
00611 _x = _x.encode('utf-8')
00612 length = len(_x)
00613 buff.write(struct.pack('<I%ss'%length, length, _x))
00614 _x = val1.link_name
00615 length = len(_x)
00616 if python3 or type(_x) == unicode:
00617 _x = _x.encode('utf-8')
00618 length = len(_x)
00619 buff.write(struct.pack('<I%ss'%length, length, _x))
00620 buff.write(_struct_i.pack(val1.type))
00621 _v32 = val1.orientation
00622 _x = _v32
00623 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00624 _x = val1
00625 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00626 length = len(self.motion_plan_request.path_constraints.visibility_constraints)
00627 buff.write(_struct_I.pack(length))
00628 for val1 in self.motion_plan_request.path_constraints.visibility_constraints:
00629 _v33 = val1.header
00630 buff.write(_struct_I.pack(_v33.seq))
00631 _v34 = _v33.stamp
00632 _x = _v34
00633 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00634 _x = _v33.frame_id
00635 length = len(_x)
00636 if python3 or type(_x) == unicode:
00637 _x = _x.encode('utf-8')
00638 length = len(_x)
00639 buff.write(struct.pack('<I%ss'%length, length, _x))
00640 _v35 = val1.target
00641 _v36 = _v35.header
00642 buff.write(_struct_I.pack(_v36.seq))
00643 _v37 = _v36.stamp
00644 _x = _v37
00645 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00646 _x = _v36.frame_id
00647 length = len(_x)
00648 if python3 or type(_x) == unicode:
00649 _x = _x.encode('utf-8')
00650 length = len(_x)
00651 buff.write(struct.pack('<I%ss'%length, length, _x))
00652 _v38 = _v35.point
00653 _x = _v38
00654 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00655 _v39 = val1.sensor_pose
00656 _v40 = _v39.header
00657 buff.write(_struct_I.pack(_v40.seq))
00658 _v41 = _v40.stamp
00659 _x = _v41
00660 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00661 _x = _v40.frame_id
00662 length = len(_x)
00663 if python3 or type(_x) == unicode:
00664 _x = _x.encode('utf-8')
00665 length = len(_x)
00666 buff.write(struct.pack('<I%ss'%length, length, _x))
00667 _v42 = _v39.pose
00668 _v43 = _v42.position
00669 _x = _v43
00670 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00671 _v44 = _v42.orientation
00672 _x = _v44
00673 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00674 buff.write(_struct_d.pack(val1.absolute_tolerance))
00675 _x = self.motion_plan_request.planner_id
00676 length = len(_x)
00677 if python3 or type(_x) == unicode:
00678 _x = _x.encode('utf-8')
00679 length = len(_x)
00680 buff.write(struct.pack('<I%ss'%length, length, _x))
00681 _x = self.motion_plan_request.group_name
00682 length = len(_x)
00683 if python3 or type(_x) == unicode:
00684 _x = _x.encode('utf-8')
00685 length = len(_x)
00686 buff.write(struct.pack('<I%ss'%length, length, _x))
00687 _x = self
00688 buff.write(_struct_7i.pack(_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs))
00689 except struct.error as se: self._check_types(se)
00690 except TypeError as te: self._check_types(te)
00691
00692 def deserialize(self, str):
00693 """
00694 unpack serialized message in str into this message instance
00695 :param str: byte array of serialized message, ``str``
00696 """
00697 try:
00698 if self.motion_plan_request is None:
00699 self.motion_plan_request = arm_navigation_msgs.msg.MotionPlanRequest()
00700 end = 0
00701 start = end
00702 end += 1
00703 (self.motion_plan_request.workspace_parameters.workspace_region_shape.type,) = _struct_b.unpack(str[start:end])
00704 start = end
00705 end += 4
00706 (length,) = _struct_I.unpack(str[start:end])
00707 pattern = '<%sd'%length
00708 start = end
00709 end += struct.calcsize(pattern)
00710 self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions = struct.unpack(pattern, str[start:end])
00711 start = end
00712 end += 4
00713 (length,) = _struct_I.unpack(str[start:end])
00714 pattern = '<%si'%length
00715 start = end
00716 end += struct.calcsize(pattern)
00717 self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles = struct.unpack(pattern, str[start:end])
00718 start = end
00719 end += 4
00720 (length,) = _struct_I.unpack(str[start:end])
00721 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices = []
00722 for i in range(0, length):
00723 val1 = geometry_msgs.msg.Point()
00724 _x = val1
00725 start = end
00726 end += 24
00727 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00728 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices.append(val1)
00729 _x = self
00730 start = end
00731 end += 12
00732 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00733 start = end
00734 end += 4
00735 (length,) = _struct_I.unpack(str[start:end])
00736 start = end
00737 end += length
00738 if python3:
00739 self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end].decode('utf-8')
00740 else:
00741 self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
00742 _x = self
00743 start = end
00744 end += 68
00745 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00746 start = end
00747 end += 4
00748 (length,) = _struct_I.unpack(str[start:end])
00749 start = end
00750 end += length
00751 if python3:
00752 self.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
00753 else:
00754 self.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end]
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 self.motion_plan_request.start_state.joint_state.name = []
00759 for i in range(0, length):
00760 start = end
00761 end += 4
00762 (length,) = _struct_I.unpack(str[start:end])
00763 start = end
00764 end += length
00765 if python3:
00766 val1 = str[start:end].decode('utf-8')
00767 else:
00768 val1 = str[start:end]
00769 self.motion_plan_request.start_state.joint_state.name.append(val1)
00770 start = end
00771 end += 4
00772 (length,) = _struct_I.unpack(str[start:end])
00773 pattern = '<%sd'%length
00774 start = end
00775 end += struct.calcsize(pattern)
00776 self.motion_plan_request.start_state.joint_state.position = struct.unpack(pattern, str[start:end])
00777 start = end
00778 end += 4
00779 (length,) = _struct_I.unpack(str[start:end])
00780 pattern = '<%sd'%length
00781 start = end
00782 end += struct.calcsize(pattern)
00783 self.motion_plan_request.start_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00784 start = end
00785 end += 4
00786 (length,) = _struct_I.unpack(str[start:end])
00787 pattern = '<%sd'%length
00788 start = end
00789 end += struct.calcsize(pattern)
00790 self.motion_plan_request.start_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00791 _x = self
00792 start = end
00793 end += 8
00794 (_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00795 start = end
00796 end += 4
00797 (length,) = _struct_I.unpack(str[start:end])
00798 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names = []
00799 for i in range(0, length):
00800 start = end
00801 end += 4
00802 (length,) = _struct_I.unpack(str[start:end])
00803 start = end
00804 end += length
00805 if python3:
00806 val1 = str[start:end].decode('utf-8')
00807 else:
00808 val1 = str[start:end]
00809 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names.append(val1)
00810 start = end
00811 end += 4
00812 (length,) = _struct_I.unpack(str[start:end])
00813 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = []
00814 for i in range(0, length):
00815 start = end
00816 end += 4
00817 (length,) = _struct_I.unpack(str[start:end])
00818 start = end
00819 end += length
00820 if python3:
00821 val1 = str[start:end].decode('utf-8')
00822 else:
00823 val1 = str[start:end]
00824 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids.append(val1)
00825 start = end
00826 end += 4
00827 (length,) = _struct_I.unpack(str[start:end])
00828 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = []
00829 for i in range(0, length):
00830 start = end
00831 end += 4
00832 (length,) = _struct_I.unpack(str[start:end])
00833 start = end
00834 end += length
00835 if python3:
00836 val1 = str[start:end].decode('utf-8')
00837 else:
00838 val1 = str[start:end]
00839 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
00840 start = end
00841 end += 4
00842 (length,) = _struct_I.unpack(str[start:end])
00843 self.motion_plan_request.start_state.multi_dof_joint_state.poses = []
00844 for i in range(0, length):
00845 val1 = geometry_msgs.msg.Pose()
00846 _v45 = val1.position
00847 _x = _v45
00848 start = end
00849 end += 24
00850 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00851 _v46 = val1.orientation
00852 _x = _v46
00853 start = end
00854 end += 32
00855 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00856 self.motion_plan_request.start_state.multi_dof_joint_state.poses.append(val1)
00857 start = end
00858 end += 4
00859 (length,) = _struct_I.unpack(str[start:end])
00860 self.motion_plan_request.goal_constraints.joint_constraints = []
00861 for i in range(0, length):
00862 val1 = arm_navigation_msgs.msg.JointConstraint()
00863 start = end
00864 end += 4
00865 (length,) = _struct_I.unpack(str[start:end])
00866 start = end
00867 end += length
00868 if python3:
00869 val1.joint_name = str[start:end].decode('utf-8')
00870 else:
00871 val1.joint_name = str[start:end]
00872 _x = val1
00873 start = end
00874 end += 32
00875 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
00876 self.motion_plan_request.goal_constraints.joint_constraints.append(val1)
00877 start = end
00878 end += 4
00879 (length,) = _struct_I.unpack(str[start:end])
00880 self.motion_plan_request.goal_constraints.position_constraints = []
00881 for i in range(0, length):
00882 val1 = arm_navigation_msgs.msg.PositionConstraint()
00883 _v47 = val1.header
00884 start = end
00885 end += 4
00886 (_v47.seq,) = _struct_I.unpack(str[start:end])
00887 _v48 = _v47.stamp
00888 _x = _v48
00889 start = end
00890 end += 8
00891 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00892 start = end
00893 end += 4
00894 (length,) = _struct_I.unpack(str[start:end])
00895 start = end
00896 end += length
00897 if python3:
00898 _v47.frame_id = str[start:end].decode('utf-8')
00899 else:
00900 _v47.frame_id = str[start:end]
00901 start = end
00902 end += 4
00903 (length,) = _struct_I.unpack(str[start:end])
00904 start = end
00905 end += length
00906 if python3:
00907 val1.link_name = str[start:end].decode('utf-8')
00908 else:
00909 val1.link_name = str[start:end]
00910 _v49 = val1.target_point_offset
00911 _x = _v49
00912 start = end
00913 end += 24
00914 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00915 _v50 = val1.position
00916 _x = _v50
00917 start = end
00918 end += 24
00919 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00920 _v51 = val1.constraint_region_shape
00921 start = end
00922 end += 1
00923 (_v51.type,) = _struct_b.unpack(str[start:end])
00924 start = end
00925 end += 4
00926 (length,) = _struct_I.unpack(str[start:end])
00927 pattern = '<%sd'%length
00928 start = end
00929 end += struct.calcsize(pattern)
00930 _v51.dimensions = struct.unpack(pattern, str[start:end])
00931 start = end
00932 end += 4
00933 (length,) = _struct_I.unpack(str[start:end])
00934 pattern = '<%si'%length
00935 start = end
00936 end += struct.calcsize(pattern)
00937 _v51.triangles = struct.unpack(pattern, str[start:end])
00938 start = end
00939 end += 4
00940 (length,) = _struct_I.unpack(str[start:end])
00941 _v51.vertices = []
00942 for i in range(0, length):
00943 val3 = geometry_msgs.msg.Point()
00944 _x = val3
00945 start = end
00946 end += 24
00947 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00948 _v51.vertices.append(val3)
00949 _v52 = val1.constraint_region_orientation
00950 _x = _v52
00951 start = end
00952 end += 32
00953 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00954 start = end
00955 end += 8
00956 (val1.weight,) = _struct_d.unpack(str[start:end])
00957 self.motion_plan_request.goal_constraints.position_constraints.append(val1)
00958 start = end
00959 end += 4
00960 (length,) = _struct_I.unpack(str[start:end])
00961 self.motion_plan_request.goal_constraints.orientation_constraints = []
00962 for i in range(0, length):
00963 val1 = arm_navigation_msgs.msg.OrientationConstraint()
00964 _v53 = val1.header
00965 start = end
00966 end += 4
00967 (_v53.seq,) = _struct_I.unpack(str[start:end])
00968 _v54 = _v53.stamp
00969 _x = _v54
00970 start = end
00971 end += 8
00972 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00973 start = end
00974 end += 4
00975 (length,) = _struct_I.unpack(str[start:end])
00976 start = end
00977 end += length
00978 if python3:
00979 _v53.frame_id = str[start:end].decode('utf-8')
00980 else:
00981 _v53.frame_id = str[start:end]
00982 start = end
00983 end += 4
00984 (length,) = _struct_I.unpack(str[start:end])
00985 start = end
00986 end += length
00987 if python3:
00988 val1.link_name = str[start:end].decode('utf-8')
00989 else:
00990 val1.link_name = str[start:end]
00991 start = end
00992 end += 4
00993 (val1.type,) = _struct_i.unpack(str[start:end])
00994 _v55 = val1.orientation
00995 _x = _v55
00996 start = end
00997 end += 32
00998 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00999 _x = val1
01000 start = end
01001 end += 32
01002 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01003 self.motion_plan_request.goal_constraints.orientation_constraints.append(val1)
01004 start = end
01005 end += 4
01006 (length,) = _struct_I.unpack(str[start:end])
01007 self.motion_plan_request.goal_constraints.visibility_constraints = []
01008 for i in range(0, length):
01009 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01010 _v56 = val1.header
01011 start = end
01012 end += 4
01013 (_v56.seq,) = _struct_I.unpack(str[start:end])
01014 _v57 = _v56.stamp
01015 _x = _v57
01016 start = end
01017 end += 8
01018 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01019 start = end
01020 end += 4
01021 (length,) = _struct_I.unpack(str[start:end])
01022 start = end
01023 end += length
01024 if python3:
01025 _v56.frame_id = str[start:end].decode('utf-8')
01026 else:
01027 _v56.frame_id = str[start:end]
01028 _v58 = val1.target
01029 _v59 = _v58.header
01030 start = end
01031 end += 4
01032 (_v59.seq,) = _struct_I.unpack(str[start:end])
01033 _v60 = _v59.stamp
01034 _x = _v60
01035 start = end
01036 end += 8
01037 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01038 start = end
01039 end += 4
01040 (length,) = _struct_I.unpack(str[start:end])
01041 start = end
01042 end += length
01043 if python3:
01044 _v59.frame_id = str[start:end].decode('utf-8')
01045 else:
01046 _v59.frame_id = str[start:end]
01047 _v61 = _v58.point
01048 _x = _v61
01049 start = end
01050 end += 24
01051 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01052 _v62 = val1.sensor_pose
01053 _v63 = _v62.header
01054 start = end
01055 end += 4
01056 (_v63.seq,) = _struct_I.unpack(str[start:end])
01057 _v64 = _v63.stamp
01058 _x = _v64
01059 start = end
01060 end += 8
01061 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01062 start = end
01063 end += 4
01064 (length,) = _struct_I.unpack(str[start:end])
01065 start = end
01066 end += length
01067 if python3:
01068 _v63.frame_id = str[start:end].decode('utf-8')
01069 else:
01070 _v63.frame_id = str[start:end]
01071 _v65 = _v62.pose
01072 _v66 = _v65.position
01073 _x = _v66
01074 start = end
01075 end += 24
01076 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01077 _v67 = _v65.orientation
01078 _x = _v67
01079 start = end
01080 end += 32
01081 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01082 start = end
01083 end += 8
01084 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01085 self.motion_plan_request.goal_constraints.visibility_constraints.append(val1)
01086 start = end
01087 end += 4
01088 (length,) = _struct_I.unpack(str[start:end])
01089 self.motion_plan_request.path_constraints.joint_constraints = []
01090 for i in range(0, length):
01091 val1 = arm_navigation_msgs.msg.JointConstraint()
01092 start = end
01093 end += 4
01094 (length,) = _struct_I.unpack(str[start:end])
01095 start = end
01096 end += length
01097 if python3:
01098 val1.joint_name = str[start:end].decode('utf-8')
01099 else:
01100 val1.joint_name = str[start:end]
01101 _x = val1
01102 start = end
01103 end += 32
01104 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01105 self.motion_plan_request.path_constraints.joint_constraints.append(val1)
01106 start = end
01107 end += 4
01108 (length,) = _struct_I.unpack(str[start:end])
01109 self.motion_plan_request.path_constraints.position_constraints = []
01110 for i in range(0, length):
01111 val1 = arm_navigation_msgs.msg.PositionConstraint()
01112 _v68 = val1.header
01113 start = end
01114 end += 4
01115 (_v68.seq,) = _struct_I.unpack(str[start:end])
01116 _v69 = _v68.stamp
01117 _x = _v69
01118 start = end
01119 end += 8
01120 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01121 start = end
01122 end += 4
01123 (length,) = _struct_I.unpack(str[start:end])
01124 start = end
01125 end += length
01126 if python3:
01127 _v68.frame_id = str[start:end].decode('utf-8')
01128 else:
01129 _v68.frame_id = str[start:end]
01130 start = end
01131 end += 4
01132 (length,) = _struct_I.unpack(str[start:end])
01133 start = end
01134 end += length
01135 if python3:
01136 val1.link_name = str[start:end].decode('utf-8')
01137 else:
01138 val1.link_name = str[start:end]
01139 _v70 = val1.target_point_offset
01140 _x = _v70
01141 start = end
01142 end += 24
01143 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01144 _v71 = val1.position
01145 _x = _v71
01146 start = end
01147 end += 24
01148 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01149 _v72 = val1.constraint_region_shape
01150 start = end
01151 end += 1
01152 (_v72.type,) = _struct_b.unpack(str[start:end])
01153 start = end
01154 end += 4
01155 (length,) = _struct_I.unpack(str[start:end])
01156 pattern = '<%sd'%length
01157 start = end
01158 end += struct.calcsize(pattern)
01159 _v72.dimensions = struct.unpack(pattern, str[start:end])
01160 start = end
01161 end += 4
01162 (length,) = _struct_I.unpack(str[start:end])
01163 pattern = '<%si'%length
01164 start = end
01165 end += struct.calcsize(pattern)
01166 _v72.triangles = struct.unpack(pattern, str[start:end])
01167 start = end
01168 end += 4
01169 (length,) = _struct_I.unpack(str[start:end])
01170 _v72.vertices = []
01171 for i in range(0, length):
01172 val3 = geometry_msgs.msg.Point()
01173 _x = val3
01174 start = end
01175 end += 24
01176 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01177 _v72.vertices.append(val3)
01178 _v73 = val1.constraint_region_orientation
01179 _x = _v73
01180 start = end
01181 end += 32
01182 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01183 start = end
01184 end += 8
01185 (val1.weight,) = _struct_d.unpack(str[start:end])
01186 self.motion_plan_request.path_constraints.position_constraints.append(val1)
01187 start = end
01188 end += 4
01189 (length,) = _struct_I.unpack(str[start:end])
01190 self.motion_plan_request.path_constraints.orientation_constraints = []
01191 for i in range(0, length):
01192 val1 = arm_navigation_msgs.msg.OrientationConstraint()
01193 _v74 = val1.header
01194 start = end
01195 end += 4
01196 (_v74.seq,) = _struct_I.unpack(str[start:end])
01197 _v75 = _v74.stamp
01198 _x = _v75
01199 start = end
01200 end += 8
01201 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01202 start = end
01203 end += 4
01204 (length,) = _struct_I.unpack(str[start:end])
01205 start = end
01206 end += length
01207 if python3:
01208 _v74.frame_id = str[start:end].decode('utf-8')
01209 else:
01210 _v74.frame_id = str[start:end]
01211 start = end
01212 end += 4
01213 (length,) = _struct_I.unpack(str[start:end])
01214 start = end
01215 end += length
01216 if python3:
01217 val1.link_name = str[start:end].decode('utf-8')
01218 else:
01219 val1.link_name = str[start:end]
01220 start = end
01221 end += 4
01222 (val1.type,) = _struct_i.unpack(str[start:end])
01223 _v76 = val1.orientation
01224 _x = _v76
01225 start = end
01226 end += 32
01227 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01228 _x = val1
01229 start = end
01230 end += 32
01231 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01232 self.motion_plan_request.path_constraints.orientation_constraints.append(val1)
01233 start = end
01234 end += 4
01235 (length,) = _struct_I.unpack(str[start:end])
01236 self.motion_plan_request.path_constraints.visibility_constraints = []
01237 for i in range(0, length):
01238 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01239 _v77 = val1.header
01240 start = end
01241 end += 4
01242 (_v77.seq,) = _struct_I.unpack(str[start:end])
01243 _v78 = _v77.stamp
01244 _x = _v78
01245 start = end
01246 end += 8
01247 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01248 start = end
01249 end += 4
01250 (length,) = _struct_I.unpack(str[start:end])
01251 start = end
01252 end += length
01253 if python3:
01254 _v77.frame_id = str[start:end].decode('utf-8')
01255 else:
01256 _v77.frame_id = str[start:end]
01257 _v79 = val1.target
01258 _v80 = _v79.header
01259 start = end
01260 end += 4
01261 (_v80.seq,) = _struct_I.unpack(str[start:end])
01262 _v81 = _v80.stamp
01263 _x = _v81
01264 start = end
01265 end += 8
01266 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01267 start = end
01268 end += 4
01269 (length,) = _struct_I.unpack(str[start:end])
01270 start = end
01271 end += length
01272 if python3:
01273 _v80.frame_id = str[start:end].decode('utf-8')
01274 else:
01275 _v80.frame_id = str[start:end]
01276 _v82 = _v79.point
01277 _x = _v82
01278 start = end
01279 end += 24
01280 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01281 _v83 = val1.sensor_pose
01282 _v84 = _v83.header
01283 start = end
01284 end += 4
01285 (_v84.seq,) = _struct_I.unpack(str[start:end])
01286 _v85 = _v84.stamp
01287 _x = _v85
01288 start = end
01289 end += 8
01290 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01291 start = end
01292 end += 4
01293 (length,) = _struct_I.unpack(str[start:end])
01294 start = end
01295 end += length
01296 if python3:
01297 _v84.frame_id = str[start:end].decode('utf-8')
01298 else:
01299 _v84.frame_id = str[start:end]
01300 _v86 = _v83.pose
01301 _v87 = _v86.position
01302 _x = _v87
01303 start = end
01304 end += 24
01305 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01306 _v88 = _v86.orientation
01307 _x = _v88
01308 start = end
01309 end += 32
01310 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01311 start = end
01312 end += 8
01313 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01314 self.motion_plan_request.path_constraints.visibility_constraints.append(val1)
01315 start = end
01316 end += 4
01317 (length,) = _struct_I.unpack(str[start:end])
01318 start = end
01319 end += length
01320 if python3:
01321 self.motion_plan_request.planner_id = str[start:end].decode('utf-8')
01322 else:
01323 self.motion_plan_request.planner_id = str[start:end]
01324 start = end
01325 end += 4
01326 (length,) = _struct_I.unpack(str[start:end])
01327 start = end
01328 end += length
01329 if python3:
01330 self.motion_plan_request.group_name = str[start:end].decode('utf-8')
01331 else:
01332 self.motion_plan_request.group_name = str[start:end]
01333 _x = self
01334 start = end
01335 end += 28
01336 (_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
01337 return self
01338 except struct.error as e:
01339 raise genpy.DeserializationError(e)
01340
01341
01342 def serialize_numpy(self, buff, numpy):
01343 """
01344 serialize message with numpy array types into buffer
01345 :param buff: buffer, ``StringIO``
01346 :param numpy: numpy python module
01347 """
01348 try:
01349 buff.write(_struct_b.pack(self.motion_plan_request.workspace_parameters.workspace_region_shape.type))
01350 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions)
01351 buff.write(_struct_I.pack(length))
01352 pattern = '<%sd'%length
01353 buff.write(self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions.tostring())
01354 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles)
01355 buff.write(_struct_I.pack(length))
01356 pattern = '<%si'%length
01357 buff.write(self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles.tostring())
01358 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices)
01359 buff.write(_struct_I.pack(length))
01360 for val1 in self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices:
01361 _x = val1
01362 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01363 _x = self
01364 buff.write(_struct_3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
01365 _x = self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id
01366 length = len(_x)
01367 if python3 or type(_x) == unicode:
01368 _x = _x.encode('utf-8')
01369 length = len(_x)
01370 buff.write(struct.pack('<I%ss'%length, length, _x))
01371 _x = self
01372 buff.write(_struct_7d3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs))
01373 _x = self.motion_plan_request.start_state.joint_state.header.frame_id
01374 length = len(_x)
01375 if python3 or type(_x) == unicode:
01376 _x = _x.encode('utf-8')
01377 length = len(_x)
01378 buff.write(struct.pack('<I%ss'%length, length, _x))
01379 length = len(self.motion_plan_request.start_state.joint_state.name)
01380 buff.write(_struct_I.pack(length))
01381 for val1 in self.motion_plan_request.start_state.joint_state.name:
01382 length = len(val1)
01383 if python3 or type(val1) == unicode:
01384 val1 = val1.encode('utf-8')
01385 length = len(val1)
01386 buff.write(struct.pack('<I%ss'%length, length, val1))
01387 length = len(self.motion_plan_request.start_state.joint_state.position)
01388 buff.write(_struct_I.pack(length))
01389 pattern = '<%sd'%length
01390 buff.write(self.motion_plan_request.start_state.joint_state.position.tostring())
01391 length = len(self.motion_plan_request.start_state.joint_state.velocity)
01392 buff.write(_struct_I.pack(length))
01393 pattern = '<%sd'%length
01394 buff.write(self.motion_plan_request.start_state.joint_state.velocity.tostring())
01395 length = len(self.motion_plan_request.start_state.joint_state.effort)
01396 buff.write(_struct_I.pack(length))
01397 pattern = '<%sd'%length
01398 buff.write(self.motion_plan_request.start_state.joint_state.effort.tostring())
01399 _x = self
01400 buff.write(_struct_2I.pack(_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs))
01401 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.joint_names)
01402 buff.write(_struct_I.pack(length))
01403 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.joint_names:
01404 length = len(val1)
01405 if python3 or type(val1) == unicode:
01406 val1 = val1.encode('utf-8')
01407 length = len(val1)
01408 buff.write(struct.pack('<I%ss'%length, length, val1))
01409 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids)
01410 buff.write(_struct_I.pack(length))
01411 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids:
01412 length = len(val1)
01413 if python3 or type(val1) == unicode:
01414 val1 = val1.encode('utf-8')
01415 length = len(val1)
01416 buff.write(struct.pack('<I%ss'%length, length, val1))
01417 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids)
01418 buff.write(_struct_I.pack(length))
01419 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids:
01420 length = len(val1)
01421 if python3 or type(val1) == unicode:
01422 val1 = val1.encode('utf-8')
01423 length = len(val1)
01424 buff.write(struct.pack('<I%ss'%length, length, val1))
01425 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.poses)
01426 buff.write(_struct_I.pack(length))
01427 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.poses:
01428 _v89 = val1.position
01429 _x = _v89
01430 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01431 _v90 = val1.orientation
01432 _x = _v90
01433 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01434 length = len(self.motion_plan_request.goal_constraints.joint_constraints)
01435 buff.write(_struct_I.pack(length))
01436 for val1 in self.motion_plan_request.goal_constraints.joint_constraints:
01437 _x = val1.joint_name
01438 length = len(_x)
01439 if python3 or type(_x) == unicode:
01440 _x = _x.encode('utf-8')
01441 length = len(_x)
01442 buff.write(struct.pack('<I%ss'%length, length, _x))
01443 _x = val1
01444 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01445 length = len(self.motion_plan_request.goal_constraints.position_constraints)
01446 buff.write(_struct_I.pack(length))
01447 for val1 in self.motion_plan_request.goal_constraints.position_constraints:
01448 _v91 = val1.header
01449 buff.write(_struct_I.pack(_v91.seq))
01450 _v92 = _v91.stamp
01451 _x = _v92
01452 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01453 _x = _v91.frame_id
01454 length = len(_x)
01455 if python3 or type(_x) == unicode:
01456 _x = _x.encode('utf-8')
01457 length = len(_x)
01458 buff.write(struct.pack('<I%ss'%length, length, _x))
01459 _x = val1.link_name
01460 length = len(_x)
01461 if python3 or type(_x) == unicode:
01462 _x = _x.encode('utf-8')
01463 length = len(_x)
01464 buff.write(struct.pack('<I%ss'%length, length, _x))
01465 _v93 = val1.target_point_offset
01466 _x = _v93
01467 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01468 _v94 = val1.position
01469 _x = _v94
01470 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01471 _v95 = val1.constraint_region_shape
01472 buff.write(_struct_b.pack(_v95.type))
01473 length = len(_v95.dimensions)
01474 buff.write(_struct_I.pack(length))
01475 pattern = '<%sd'%length
01476 buff.write(_v95.dimensions.tostring())
01477 length = len(_v95.triangles)
01478 buff.write(_struct_I.pack(length))
01479 pattern = '<%si'%length
01480 buff.write(_v95.triangles.tostring())
01481 length = len(_v95.vertices)
01482 buff.write(_struct_I.pack(length))
01483 for val3 in _v95.vertices:
01484 _x = val3
01485 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01486 _v96 = val1.constraint_region_orientation
01487 _x = _v96
01488 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01489 buff.write(_struct_d.pack(val1.weight))
01490 length = len(self.motion_plan_request.goal_constraints.orientation_constraints)
01491 buff.write(_struct_I.pack(length))
01492 for val1 in self.motion_plan_request.goal_constraints.orientation_constraints:
01493 _v97 = val1.header
01494 buff.write(_struct_I.pack(_v97.seq))
01495 _v98 = _v97.stamp
01496 _x = _v98
01497 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01498 _x = _v97.frame_id
01499 length = len(_x)
01500 if python3 or type(_x) == unicode:
01501 _x = _x.encode('utf-8')
01502 length = len(_x)
01503 buff.write(struct.pack('<I%ss'%length, length, _x))
01504 _x = val1.link_name
01505 length = len(_x)
01506 if python3 or type(_x) == unicode:
01507 _x = _x.encode('utf-8')
01508 length = len(_x)
01509 buff.write(struct.pack('<I%ss'%length, length, _x))
01510 buff.write(_struct_i.pack(val1.type))
01511 _v99 = val1.orientation
01512 _x = _v99
01513 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01514 _x = val1
01515 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01516 length = len(self.motion_plan_request.goal_constraints.visibility_constraints)
01517 buff.write(_struct_I.pack(length))
01518 for val1 in self.motion_plan_request.goal_constraints.visibility_constraints:
01519 _v100 = val1.header
01520 buff.write(_struct_I.pack(_v100.seq))
01521 _v101 = _v100.stamp
01522 _x = _v101
01523 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01524 _x = _v100.frame_id
01525 length = len(_x)
01526 if python3 or type(_x) == unicode:
01527 _x = _x.encode('utf-8')
01528 length = len(_x)
01529 buff.write(struct.pack('<I%ss'%length, length, _x))
01530 _v102 = val1.target
01531 _v103 = _v102.header
01532 buff.write(_struct_I.pack(_v103.seq))
01533 _v104 = _v103.stamp
01534 _x = _v104
01535 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01536 _x = _v103.frame_id
01537 length = len(_x)
01538 if python3 or type(_x) == unicode:
01539 _x = _x.encode('utf-8')
01540 length = len(_x)
01541 buff.write(struct.pack('<I%ss'%length, length, _x))
01542 _v105 = _v102.point
01543 _x = _v105
01544 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01545 _v106 = val1.sensor_pose
01546 _v107 = _v106.header
01547 buff.write(_struct_I.pack(_v107.seq))
01548 _v108 = _v107.stamp
01549 _x = _v108
01550 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01551 _x = _v107.frame_id
01552 length = len(_x)
01553 if python3 or type(_x) == unicode:
01554 _x = _x.encode('utf-8')
01555 length = len(_x)
01556 buff.write(struct.pack('<I%ss'%length, length, _x))
01557 _v109 = _v106.pose
01558 _v110 = _v109.position
01559 _x = _v110
01560 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01561 _v111 = _v109.orientation
01562 _x = _v111
01563 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01564 buff.write(_struct_d.pack(val1.absolute_tolerance))
01565 length = len(self.motion_plan_request.path_constraints.joint_constraints)
01566 buff.write(_struct_I.pack(length))
01567 for val1 in self.motion_plan_request.path_constraints.joint_constraints:
01568 _x = val1.joint_name
01569 length = len(_x)
01570 if python3 or type(_x) == unicode:
01571 _x = _x.encode('utf-8')
01572 length = len(_x)
01573 buff.write(struct.pack('<I%ss'%length, length, _x))
01574 _x = val1
01575 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01576 length = len(self.motion_plan_request.path_constraints.position_constraints)
01577 buff.write(_struct_I.pack(length))
01578 for val1 in self.motion_plan_request.path_constraints.position_constraints:
01579 _v112 = val1.header
01580 buff.write(_struct_I.pack(_v112.seq))
01581 _v113 = _v112.stamp
01582 _x = _v113
01583 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01584 _x = _v112.frame_id
01585 length = len(_x)
01586 if python3 or type(_x) == unicode:
01587 _x = _x.encode('utf-8')
01588 length = len(_x)
01589 buff.write(struct.pack('<I%ss'%length, length, _x))
01590 _x = val1.link_name
01591 length = len(_x)
01592 if python3 or type(_x) == unicode:
01593 _x = _x.encode('utf-8')
01594 length = len(_x)
01595 buff.write(struct.pack('<I%ss'%length, length, _x))
01596 _v114 = val1.target_point_offset
01597 _x = _v114
01598 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01599 _v115 = val1.position
01600 _x = _v115
01601 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01602 _v116 = val1.constraint_region_shape
01603 buff.write(_struct_b.pack(_v116.type))
01604 length = len(_v116.dimensions)
01605 buff.write(_struct_I.pack(length))
01606 pattern = '<%sd'%length
01607 buff.write(_v116.dimensions.tostring())
01608 length = len(_v116.triangles)
01609 buff.write(_struct_I.pack(length))
01610 pattern = '<%si'%length
01611 buff.write(_v116.triangles.tostring())
01612 length = len(_v116.vertices)
01613 buff.write(_struct_I.pack(length))
01614 for val3 in _v116.vertices:
01615 _x = val3
01616 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01617 _v117 = val1.constraint_region_orientation
01618 _x = _v117
01619 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01620 buff.write(_struct_d.pack(val1.weight))
01621 length = len(self.motion_plan_request.path_constraints.orientation_constraints)
01622 buff.write(_struct_I.pack(length))
01623 for val1 in self.motion_plan_request.path_constraints.orientation_constraints:
01624 _v118 = val1.header
01625 buff.write(_struct_I.pack(_v118.seq))
01626 _v119 = _v118.stamp
01627 _x = _v119
01628 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01629 _x = _v118.frame_id
01630 length = len(_x)
01631 if python3 or type(_x) == unicode:
01632 _x = _x.encode('utf-8')
01633 length = len(_x)
01634 buff.write(struct.pack('<I%ss'%length, length, _x))
01635 _x = val1.link_name
01636 length = len(_x)
01637 if python3 or type(_x) == unicode:
01638 _x = _x.encode('utf-8')
01639 length = len(_x)
01640 buff.write(struct.pack('<I%ss'%length, length, _x))
01641 buff.write(_struct_i.pack(val1.type))
01642 _v120 = val1.orientation
01643 _x = _v120
01644 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01645 _x = val1
01646 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01647 length = len(self.motion_plan_request.path_constraints.visibility_constraints)
01648 buff.write(_struct_I.pack(length))
01649 for val1 in self.motion_plan_request.path_constraints.visibility_constraints:
01650 _v121 = val1.header
01651 buff.write(_struct_I.pack(_v121.seq))
01652 _v122 = _v121.stamp
01653 _x = _v122
01654 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01655 _x = _v121.frame_id
01656 length = len(_x)
01657 if python3 or type(_x) == unicode:
01658 _x = _x.encode('utf-8')
01659 length = len(_x)
01660 buff.write(struct.pack('<I%ss'%length, length, _x))
01661 _v123 = val1.target
01662 _v124 = _v123.header
01663 buff.write(_struct_I.pack(_v124.seq))
01664 _v125 = _v124.stamp
01665 _x = _v125
01666 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01667 _x = _v124.frame_id
01668 length = len(_x)
01669 if python3 or type(_x) == unicode:
01670 _x = _x.encode('utf-8')
01671 length = len(_x)
01672 buff.write(struct.pack('<I%ss'%length, length, _x))
01673 _v126 = _v123.point
01674 _x = _v126
01675 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01676 _v127 = val1.sensor_pose
01677 _v128 = _v127.header
01678 buff.write(_struct_I.pack(_v128.seq))
01679 _v129 = _v128.stamp
01680 _x = _v129
01681 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01682 _x = _v128.frame_id
01683 length = len(_x)
01684 if python3 or type(_x) == unicode:
01685 _x = _x.encode('utf-8')
01686 length = len(_x)
01687 buff.write(struct.pack('<I%ss'%length, length, _x))
01688 _v130 = _v127.pose
01689 _v131 = _v130.position
01690 _x = _v131
01691 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01692 _v132 = _v130.orientation
01693 _x = _v132
01694 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01695 buff.write(_struct_d.pack(val1.absolute_tolerance))
01696 _x = self.motion_plan_request.planner_id
01697 length = len(_x)
01698 if python3 or type(_x) == unicode:
01699 _x = _x.encode('utf-8')
01700 length = len(_x)
01701 buff.write(struct.pack('<I%ss'%length, length, _x))
01702 _x = self.motion_plan_request.group_name
01703 length = len(_x)
01704 if python3 or type(_x) == unicode:
01705 _x = _x.encode('utf-8')
01706 length = len(_x)
01707 buff.write(struct.pack('<I%ss'%length, length, _x))
01708 _x = self
01709 buff.write(_struct_7i.pack(_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs))
01710 except struct.error as se: self._check_types(se)
01711 except TypeError as te: self._check_types(te)
01712
01713 def deserialize_numpy(self, str, numpy):
01714 """
01715 unpack serialized message in str into this message instance using numpy for array types
01716 :param str: byte array of serialized message, ``str``
01717 :param numpy: numpy python module
01718 """
01719 try:
01720 if self.motion_plan_request is None:
01721 self.motion_plan_request = arm_navigation_msgs.msg.MotionPlanRequest()
01722 end = 0
01723 start = end
01724 end += 1
01725 (self.motion_plan_request.workspace_parameters.workspace_region_shape.type,) = _struct_b.unpack(str[start:end])
01726 start = end
01727 end += 4
01728 (length,) = _struct_I.unpack(str[start:end])
01729 pattern = '<%sd'%length
01730 start = end
01731 end += struct.calcsize(pattern)
01732 self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01733 start = end
01734 end += 4
01735 (length,) = _struct_I.unpack(str[start:end])
01736 pattern = '<%si'%length
01737 start = end
01738 end += struct.calcsize(pattern)
01739 self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01740 start = end
01741 end += 4
01742 (length,) = _struct_I.unpack(str[start:end])
01743 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices = []
01744 for i in range(0, length):
01745 val1 = geometry_msgs.msg.Point()
01746 _x = val1
01747 start = end
01748 end += 24
01749 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01750 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices.append(val1)
01751 _x = self
01752 start = end
01753 end += 12
01754 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01755 start = end
01756 end += 4
01757 (length,) = _struct_I.unpack(str[start:end])
01758 start = end
01759 end += length
01760 if python3:
01761 self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end].decode('utf-8')
01762 else:
01763 self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
01764 _x = self
01765 start = end
01766 end += 68
01767 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
01768 start = end
01769 end += 4
01770 (length,) = _struct_I.unpack(str[start:end])
01771 start = end
01772 end += length
01773 if python3:
01774 self.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
01775 else:
01776 self.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end]
01777 start = end
01778 end += 4
01779 (length,) = _struct_I.unpack(str[start:end])
01780 self.motion_plan_request.start_state.joint_state.name = []
01781 for i in range(0, length):
01782 start = end
01783 end += 4
01784 (length,) = _struct_I.unpack(str[start:end])
01785 start = end
01786 end += length
01787 if python3:
01788 val1 = str[start:end].decode('utf-8')
01789 else:
01790 val1 = str[start:end]
01791 self.motion_plan_request.start_state.joint_state.name.append(val1)
01792 start = end
01793 end += 4
01794 (length,) = _struct_I.unpack(str[start:end])
01795 pattern = '<%sd'%length
01796 start = end
01797 end += struct.calcsize(pattern)
01798 self.motion_plan_request.start_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01799 start = end
01800 end += 4
01801 (length,) = _struct_I.unpack(str[start:end])
01802 pattern = '<%sd'%length
01803 start = end
01804 end += struct.calcsize(pattern)
01805 self.motion_plan_request.start_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01806 start = end
01807 end += 4
01808 (length,) = _struct_I.unpack(str[start:end])
01809 pattern = '<%sd'%length
01810 start = end
01811 end += struct.calcsize(pattern)
01812 self.motion_plan_request.start_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01813 _x = self
01814 start = end
01815 end += 8
01816 (_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01817 start = end
01818 end += 4
01819 (length,) = _struct_I.unpack(str[start:end])
01820 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names = []
01821 for i in range(0, length):
01822 start = end
01823 end += 4
01824 (length,) = _struct_I.unpack(str[start:end])
01825 start = end
01826 end += length
01827 if python3:
01828 val1 = str[start:end].decode('utf-8')
01829 else:
01830 val1 = str[start:end]
01831 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names.append(val1)
01832 start = end
01833 end += 4
01834 (length,) = _struct_I.unpack(str[start:end])
01835 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = []
01836 for i in range(0, length):
01837 start = end
01838 end += 4
01839 (length,) = _struct_I.unpack(str[start:end])
01840 start = end
01841 end += length
01842 if python3:
01843 val1 = str[start:end].decode('utf-8')
01844 else:
01845 val1 = str[start:end]
01846 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids.append(val1)
01847 start = end
01848 end += 4
01849 (length,) = _struct_I.unpack(str[start:end])
01850 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = []
01851 for i in range(0, length):
01852 start = end
01853 end += 4
01854 (length,) = _struct_I.unpack(str[start:end])
01855 start = end
01856 end += length
01857 if python3:
01858 val1 = str[start:end].decode('utf-8')
01859 else:
01860 val1 = str[start:end]
01861 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
01862 start = end
01863 end += 4
01864 (length,) = _struct_I.unpack(str[start:end])
01865 self.motion_plan_request.start_state.multi_dof_joint_state.poses = []
01866 for i in range(0, length):
01867 val1 = geometry_msgs.msg.Pose()
01868 _v133 = val1.position
01869 _x = _v133
01870 start = end
01871 end += 24
01872 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01873 _v134 = val1.orientation
01874 _x = _v134
01875 start = end
01876 end += 32
01877 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01878 self.motion_plan_request.start_state.multi_dof_joint_state.poses.append(val1)
01879 start = end
01880 end += 4
01881 (length,) = _struct_I.unpack(str[start:end])
01882 self.motion_plan_request.goal_constraints.joint_constraints = []
01883 for i in range(0, length):
01884 val1 = arm_navigation_msgs.msg.JointConstraint()
01885 start = end
01886 end += 4
01887 (length,) = _struct_I.unpack(str[start:end])
01888 start = end
01889 end += length
01890 if python3:
01891 val1.joint_name = str[start:end].decode('utf-8')
01892 else:
01893 val1.joint_name = str[start:end]
01894 _x = val1
01895 start = end
01896 end += 32
01897 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01898 self.motion_plan_request.goal_constraints.joint_constraints.append(val1)
01899 start = end
01900 end += 4
01901 (length,) = _struct_I.unpack(str[start:end])
01902 self.motion_plan_request.goal_constraints.position_constraints = []
01903 for i in range(0, length):
01904 val1 = arm_navigation_msgs.msg.PositionConstraint()
01905 _v135 = val1.header
01906 start = end
01907 end += 4
01908 (_v135.seq,) = _struct_I.unpack(str[start:end])
01909 _v136 = _v135.stamp
01910 _x = _v136
01911 start = end
01912 end += 8
01913 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01914 start = end
01915 end += 4
01916 (length,) = _struct_I.unpack(str[start:end])
01917 start = end
01918 end += length
01919 if python3:
01920 _v135.frame_id = str[start:end].decode('utf-8')
01921 else:
01922 _v135.frame_id = str[start:end]
01923 start = end
01924 end += 4
01925 (length,) = _struct_I.unpack(str[start:end])
01926 start = end
01927 end += length
01928 if python3:
01929 val1.link_name = str[start:end].decode('utf-8')
01930 else:
01931 val1.link_name = str[start:end]
01932 _v137 = val1.target_point_offset
01933 _x = _v137
01934 start = end
01935 end += 24
01936 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01937 _v138 = val1.position
01938 _x = _v138
01939 start = end
01940 end += 24
01941 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01942 _v139 = val1.constraint_region_shape
01943 start = end
01944 end += 1
01945 (_v139.type,) = _struct_b.unpack(str[start:end])
01946 start = end
01947 end += 4
01948 (length,) = _struct_I.unpack(str[start:end])
01949 pattern = '<%sd'%length
01950 start = end
01951 end += struct.calcsize(pattern)
01952 _v139.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01953 start = end
01954 end += 4
01955 (length,) = _struct_I.unpack(str[start:end])
01956 pattern = '<%si'%length
01957 start = end
01958 end += struct.calcsize(pattern)
01959 _v139.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01960 start = end
01961 end += 4
01962 (length,) = _struct_I.unpack(str[start:end])
01963 _v139.vertices = []
01964 for i in range(0, length):
01965 val3 = geometry_msgs.msg.Point()
01966 _x = val3
01967 start = end
01968 end += 24
01969 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01970 _v139.vertices.append(val3)
01971 _v140 = val1.constraint_region_orientation
01972 _x = _v140
01973 start = end
01974 end += 32
01975 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01976 start = end
01977 end += 8
01978 (val1.weight,) = _struct_d.unpack(str[start:end])
01979 self.motion_plan_request.goal_constraints.position_constraints.append(val1)
01980 start = end
01981 end += 4
01982 (length,) = _struct_I.unpack(str[start:end])
01983 self.motion_plan_request.goal_constraints.orientation_constraints = []
01984 for i in range(0, length):
01985 val1 = arm_navigation_msgs.msg.OrientationConstraint()
01986 _v141 = val1.header
01987 start = end
01988 end += 4
01989 (_v141.seq,) = _struct_I.unpack(str[start:end])
01990 _v142 = _v141.stamp
01991 _x = _v142
01992 start = end
01993 end += 8
01994 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01995 start = end
01996 end += 4
01997 (length,) = _struct_I.unpack(str[start:end])
01998 start = end
01999 end += length
02000 if python3:
02001 _v141.frame_id = str[start:end].decode('utf-8')
02002 else:
02003 _v141.frame_id = str[start:end]
02004 start = end
02005 end += 4
02006 (length,) = _struct_I.unpack(str[start:end])
02007 start = end
02008 end += length
02009 if python3:
02010 val1.link_name = str[start:end].decode('utf-8')
02011 else:
02012 val1.link_name = str[start:end]
02013 start = end
02014 end += 4
02015 (val1.type,) = _struct_i.unpack(str[start:end])
02016 _v143 = val1.orientation
02017 _x = _v143
02018 start = end
02019 end += 32
02020 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02021 _x = val1
02022 start = end
02023 end += 32
02024 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02025 self.motion_plan_request.goal_constraints.orientation_constraints.append(val1)
02026 start = end
02027 end += 4
02028 (length,) = _struct_I.unpack(str[start:end])
02029 self.motion_plan_request.goal_constraints.visibility_constraints = []
02030 for i in range(0, length):
02031 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02032 _v144 = val1.header
02033 start = end
02034 end += 4
02035 (_v144.seq,) = _struct_I.unpack(str[start:end])
02036 _v145 = _v144.stamp
02037 _x = _v145
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 _v144.frame_id = str[start:end].decode('utf-8')
02048 else:
02049 _v144.frame_id = str[start:end]
02050 _v146 = val1.target
02051 _v147 = _v146.header
02052 start = end
02053 end += 4
02054 (_v147.seq,) = _struct_I.unpack(str[start:end])
02055 _v148 = _v147.stamp
02056 _x = _v148
02057 start = end
02058 end += 8
02059 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02060 start = end
02061 end += 4
02062 (length,) = _struct_I.unpack(str[start:end])
02063 start = end
02064 end += length
02065 if python3:
02066 _v147.frame_id = str[start:end].decode('utf-8')
02067 else:
02068 _v147.frame_id = str[start:end]
02069 _v149 = _v146.point
02070 _x = _v149
02071 start = end
02072 end += 24
02073 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02074 _v150 = val1.sensor_pose
02075 _v151 = _v150.header
02076 start = end
02077 end += 4
02078 (_v151.seq,) = _struct_I.unpack(str[start:end])
02079 _v152 = _v151.stamp
02080 _x = _v152
02081 start = end
02082 end += 8
02083 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02084 start = end
02085 end += 4
02086 (length,) = _struct_I.unpack(str[start:end])
02087 start = end
02088 end += length
02089 if python3:
02090 _v151.frame_id = str[start:end].decode('utf-8')
02091 else:
02092 _v151.frame_id = str[start:end]
02093 _v153 = _v150.pose
02094 _v154 = _v153.position
02095 _x = _v154
02096 start = end
02097 end += 24
02098 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02099 _v155 = _v153.orientation
02100 _x = _v155
02101 start = end
02102 end += 32
02103 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02104 start = end
02105 end += 8
02106 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02107 self.motion_plan_request.goal_constraints.visibility_constraints.append(val1)
02108 start = end
02109 end += 4
02110 (length,) = _struct_I.unpack(str[start:end])
02111 self.motion_plan_request.path_constraints.joint_constraints = []
02112 for i in range(0, length):
02113 val1 = arm_navigation_msgs.msg.JointConstraint()
02114 start = end
02115 end += 4
02116 (length,) = _struct_I.unpack(str[start:end])
02117 start = end
02118 end += length
02119 if python3:
02120 val1.joint_name = str[start:end].decode('utf-8')
02121 else:
02122 val1.joint_name = str[start:end]
02123 _x = val1
02124 start = end
02125 end += 32
02126 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02127 self.motion_plan_request.path_constraints.joint_constraints.append(val1)
02128 start = end
02129 end += 4
02130 (length,) = _struct_I.unpack(str[start:end])
02131 self.motion_plan_request.path_constraints.position_constraints = []
02132 for i in range(0, length):
02133 val1 = arm_navigation_msgs.msg.PositionConstraint()
02134 _v156 = val1.header
02135 start = end
02136 end += 4
02137 (_v156.seq,) = _struct_I.unpack(str[start:end])
02138 _v157 = _v156.stamp
02139 _x = _v157
02140 start = end
02141 end += 8
02142 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02143 start = end
02144 end += 4
02145 (length,) = _struct_I.unpack(str[start:end])
02146 start = end
02147 end += length
02148 if python3:
02149 _v156.frame_id = str[start:end].decode('utf-8')
02150 else:
02151 _v156.frame_id = str[start:end]
02152 start = end
02153 end += 4
02154 (length,) = _struct_I.unpack(str[start:end])
02155 start = end
02156 end += length
02157 if python3:
02158 val1.link_name = str[start:end].decode('utf-8')
02159 else:
02160 val1.link_name = str[start:end]
02161 _v158 = val1.target_point_offset
02162 _x = _v158
02163 start = end
02164 end += 24
02165 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02166 _v159 = val1.position
02167 _x = _v159
02168 start = end
02169 end += 24
02170 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02171 _v160 = val1.constraint_region_shape
02172 start = end
02173 end += 1
02174 (_v160.type,) = _struct_b.unpack(str[start:end])
02175 start = end
02176 end += 4
02177 (length,) = _struct_I.unpack(str[start:end])
02178 pattern = '<%sd'%length
02179 start = end
02180 end += struct.calcsize(pattern)
02181 _v160.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02182 start = end
02183 end += 4
02184 (length,) = _struct_I.unpack(str[start:end])
02185 pattern = '<%si'%length
02186 start = end
02187 end += struct.calcsize(pattern)
02188 _v160.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02189 start = end
02190 end += 4
02191 (length,) = _struct_I.unpack(str[start:end])
02192 _v160.vertices = []
02193 for i in range(0, length):
02194 val3 = geometry_msgs.msg.Point()
02195 _x = val3
02196 start = end
02197 end += 24
02198 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02199 _v160.vertices.append(val3)
02200 _v161 = val1.constraint_region_orientation
02201 _x = _v161
02202 start = end
02203 end += 32
02204 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02205 start = end
02206 end += 8
02207 (val1.weight,) = _struct_d.unpack(str[start:end])
02208 self.motion_plan_request.path_constraints.position_constraints.append(val1)
02209 start = end
02210 end += 4
02211 (length,) = _struct_I.unpack(str[start:end])
02212 self.motion_plan_request.path_constraints.orientation_constraints = []
02213 for i in range(0, length):
02214 val1 = arm_navigation_msgs.msg.OrientationConstraint()
02215 _v162 = val1.header
02216 start = end
02217 end += 4
02218 (_v162.seq,) = _struct_I.unpack(str[start:end])
02219 _v163 = _v162.stamp
02220 _x = _v163
02221 start = end
02222 end += 8
02223 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02224 start = end
02225 end += 4
02226 (length,) = _struct_I.unpack(str[start:end])
02227 start = end
02228 end += length
02229 if python3:
02230 _v162.frame_id = str[start:end].decode('utf-8')
02231 else:
02232 _v162.frame_id = str[start:end]
02233 start = end
02234 end += 4
02235 (length,) = _struct_I.unpack(str[start:end])
02236 start = end
02237 end += length
02238 if python3:
02239 val1.link_name = str[start:end].decode('utf-8')
02240 else:
02241 val1.link_name = str[start:end]
02242 start = end
02243 end += 4
02244 (val1.type,) = _struct_i.unpack(str[start:end])
02245 _v164 = val1.orientation
02246 _x = _v164
02247 start = end
02248 end += 32
02249 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02250 _x = val1
02251 start = end
02252 end += 32
02253 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02254 self.motion_plan_request.path_constraints.orientation_constraints.append(val1)
02255 start = end
02256 end += 4
02257 (length,) = _struct_I.unpack(str[start:end])
02258 self.motion_plan_request.path_constraints.visibility_constraints = []
02259 for i in range(0, length):
02260 val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02261 _v165 = val1.header
02262 start = end
02263 end += 4
02264 (_v165.seq,) = _struct_I.unpack(str[start:end])
02265 _v166 = _v165.stamp
02266 _x = _v166
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 _v165.frame_id = str[start:end].decode('utf-8')
02277 else:
02278 _v165.frame_id = str[start:end]
02279 _v167 = val1.target
02280 _v168 = _v167.header
02281 start = end
02282 end += 4
02283 (_v168.seq,) = _struct_I.unpack(str[start:end])
02284 _v169 = _v168.stamp
02285 _x = _v169
02286 start = end
02287 end += 8
02288 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02289 start = end
02290 end += 4
02291 (length,) = _struct_I.unpack(str[start:end])
02292 start = end
02293 end += length
02294 if python3:
02295 _v168.frame_id = str[start:end].decode('utf-8')
02296 else:
02297 _v168.frame_id = str[start:end]
02298 _v170 = _v167.point
02299 _x = _v170
02300 start = end
02301 end += 24
02302 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02303 _v171 = val1.sensor_pose
02304 _v172 = _v171.header
02305 start = end
02306 end += 4
02307 (_v172.seq,) = _struct_I.unpack(str[start:end])
02308 _v173 = _v172.stamp
02309 _x = _v173
02310 start = end
02311 end += 8
02312 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02313 start = end
02314 end += 4
02315 (length,) = _struct_I.unpack(str[start:end])
02316 start = end
02317 end += length
02318 if python3:
02319 _v172.frame_id = str[start:end].decode('utf-8')
02320 else:
02321 _v172.frame_id = str[start:end]
02322 _v174 = _v171.pose
02323 _v175 = _v174.position
02324 _x = _v175
02325 start = end
02326 end += 24
02327 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02328 _v176 = _v174.orientation
02329 _x = _v176
02330 start = end
02331 end += 32
02332 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02333 start = end
02334 end += 8
02335 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02336 self.motion_plan_request.path_constraints.visibility_constraints.append(val1)
02337 start = end
02338 end += 4
02339 (length,) = _struct_I.unpack(str[start:end])
02340 start = end
02341 end += length
02342 if python3:
02343 self.motion_plan_request.planner_id = str[start:end].decode('utf-8')
02344 else:
02345 self.motion_plan_request.planner_id = str[start:end]
02346 start = end
02347 end += 4
02348 (length,) = _struct_I.unpack(str[start:end])
02349 start = end
02350 end += length
02351 if python3:
02352 self.motion_plan_request.group_name = str[start:end].decode('utf-8')
02353 else:
02354 self.motion_plan_request.group_name = str[start:end]
02355 _x = self
02356 start = end
02357 end += 28
02358 (_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
02359 return self
02360 except struct.error as e:
02361 raise genpy.DeserializationError(e)
02362
02363 _struct_I = genpy.struct_I
02364 _struct_b = struct.Struct("<b")
02365 _struct_d = struct.Struct("<d")
02366 _struct_7i = struct.Struct("<7i")
02367 _struct_2I = struct.Struct("<2I")
02368 _struct_i = struct.Struct("<i")
02369 _struct_3I = struct.Struct("<3I")
02370 _struct_4d = struct.Struct("<4d")
02371 _struct_7d3I = struct.Struct("<7d3I")
02372 _struct_3d = struct.Struct("<3d")
02373 """autogenerated by genpy from arm_navigation_msgs/GetMotionPlanResponse.msg. Do not edit."""
02374 import sys
02375 python3 = True if sys.hexversion > 0x03000000 else False
02376 import genpy
02377 import struct
02378
02379 import arm_navigation_msgs.msg
02380 import trajectory_msgs.msg
02381 import geometry_msgs.msg
02382 import sensor_msgs.msg
02383 import genpy
02384 import std_msgs.msg
02385
02386 class GetMotionPlanResponse(genpy.Message):
02387 _md5sum = "644f3b4cf5b71b614298ce1d1a472b61"
02388 _type = "arm_navigation_msgs/GetMotionPlanResponse"
02389 _has_header = False
02390 _full_text = """
02391
02392 arm_navigation_msgs/RobotTrajectory trajectory
02393
02394
02395 arm_navigation_msgs/RobotState robot_state
02396
02397
02398 duration planning_time
02399
02400
02401 arm_navigation_msgs/ArmNavigationErrorCodes error_code
02402
02403
02404 arm_navigation_msgs/ArmNavigationErrorCodes[] trajectory_error_codes
02405
02406
02407 ================================================================================
02408 MSG: arm_navigation_msgs/RobotTrajectory
02409 trajectory_msgs/JointTrajectory joint_trajectory
02410 arm_navigation_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory
02411
02412 ================================================================================
02413 MSG: trajectory_msgs/JointTrajectory
02414 Header header
02415 string[] joint_names
02416 JointTrajectoryPoint[] points
02417 ================================================================================
02418 MSG: std_msgs/Header
02419 # Standard metadata for higher-level stamped data types.
02420 # This is generally used to communicate timestamped data
02421 # in a particular coordinate frame.
02422 #
02423 # sequence ID: consecutively increasing ID
02424 uint32 seq
02425 #Two-integer timestamp that is expressed as:
02426 # * stamp.secs: seconds (stamp_secs) since epoch
02427 # * stamp.nsecs: nanoseconds since stamp_secs
02428 # time-handling sugar is provided by the client library
02429 time stamp
02430 #Frame this data is associated with
02431 # 0: no frame
02432 # 1: global frame
02433 string frame_id
02434
02435 ================================================================================
02436 MSG: trajectory_msgs/JointTrajectoryPoint
02437 float64[] positions
02438 float64[] velocities
02439 float64[] accelerations
02440 duration time_from_start
02441 ================================================================================
02442 MSG: arm_navigation_msgs/MultiDOFJointTrajectory
02443 #A representation of a multi-dof joint trajectory
02444 duration stamp
02445 string[] joint_names
02446 string[] frame_ids
02447 string[] child_frame_ids
02448 MultiDOFJointTrajectoryPoint[] points
02449
02450 ================================================================================
02451 MSG: arm_navigation_msgs/MultiDOFJointTrajectoryPoint
02452 geometry_msgs/Pose[] poses
02453 duration time_from_start
02454 ================================================================================
02455 MSG: geometry_msgs/Pose
02456 # A representation of pose in free space, composed of postion and orientation.
02457 Point position
02458 Quaternion orientation
02459
02460 ================================================================================
02461 MSG: geometry_msgs/Point
02462 # This contains the position of a point in free space
02463 float64 x
02464 float64 y
02465 float64 z
02466
02467 ================================================================================
02468 MSG: geometry_msgs/Quaternion
02469 # This represents an orientation in free space in quaternion form.
02470
02471 float64 x
02472 float64 y
02473 float64 z
02474 float64 w
02475
02476 ================================================================================
02477 MSG: arm_navigation_msgs/RobotState
02478 # This message contains information about the robot state, i.e. the positions of its joints and links
02479 sensor_msgs/JointState joint_state
02480 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
02481
02482 ================================================================================
02483 MSG: sensor_msgs/JointState
02484 # This is a message that holds data to describe the state of a set of torque controlled joints.
02485 #
02486 # The state of each joint (revolute or prismatic) is defined by:
02487 # * the position of the joint (rad or m),
02488 # * the velocity of the joint (rad/s or m/s) and
02489 # * the effort that is applied in the joint (Nm or N).
02490 #
02491 # Each joint is uniquely identified by its name
02492 # The header specifies the time at which the joint states were recorded. All the joint states
02493 # in one message have to be recorded at the same time.
02494 #
02495 # This message consists of a multiple arrays, one for each part of the joint state.
02496 # The goal is to make each of the fields optional. When e.g. your joints have no
02497 # effort associated with them, you can leave the effort array empty.
02498 #
02499 # All arrays in this message should have the same size, or be empty.
02500 # This is the only way to uniquely associate the joint name with the correct
02501 # states.
02502
02503
02504 Header header
02505
02506 string[] name
02507 float64[] position
02508 float64[] velocity
02509 float64[] effort
02510
02511 ================================================================================
02512 MSG: arm_navigation_msgs/MultiDOFJointState
02513 #A representation of a multi-dof joint state
02514 time stamp
02515 string[] joint_names
02516 string[] frame_ids
02517 string[] child_frame_ids
02518 geometry_msgs/Pose[] poses
02519
02520 ================================================================================
02521 MSG: arm_navigation_msgs/ArmNavigationErrorCodes
02522 int32 val
02523
02524 # overall behavior
02525 int32 PLANNING_FAILED=-1
02526 int32 SUCCESS=1
02527 int32 TIMED_OUT=-2
02528
02529 # start state errors
02530 int32 START_STATE_IN_COLLISION=-3
02531 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
02532
02533 # goal errors
02534 int32 GOAL_IN_COLLISION=-5
02535 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
02536
02537 # robot state
02538 int32 INVALID_ROBOT_STATE=-7
02539 int32 INCOMPLETE_ROBOT_STATE=-8
02540
02541 # planning request errors
02542 int32 INVALID_PLANNER_ID=-9
02543 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
02544 int32 INVALID_ALLOWED_PLANNING_TIME=-11
02545 int32 INVALID_GROUP_NAME=-12
02546 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
02547 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
02548 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
02549 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
02550 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
02551 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
02552
02553 # state/trajectory monitor errors
02554 int32 INVALID_TRAJECTORY=-19
02555 int32 INVALID_INDEX=-20
02556 int32 JOINT_LIMITS_VIOLATED=-21
02557 int32 PATH_CONSTRAINTS_VIOLATED=-22
02558 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
02559 int32 GOAL_CONSTRAINTS_VIOLATED=-24
02560 int32 JOINTS_NOT_MOVING=-25
02561 int32 TRAJECTORY_CONTROLLER_FAILED=-26
02562
02563 # system errors
02564 int32 FRAME_TRANSFORM_FAILURE=-27
02565 int32 COLLISION_CHECKING_UNAVAILABLE=-28
02566 int32 ROBOT_STATE_STALE=-29
02567 int32 SENSOR_INFO_STALE=-30
02568
02569 # kinematics errors
02570 int32 NO_IK_SOLUTION=-31
02571 int32 INVALID_LINK_NAME=-32
02572 int32 IK_LINK_IN_COLLISION=-33
02573 int32 NO_FK_SOLUTION=-34
02574 int32 KINEMATICS_STATE_IN_COLLISION=-35
02575
02576 # general errors
02577 int32 INVALID_TIMEOUT=-36
02578
02579
02580 """
02581 __slots__ = ['trajectory','robot_state','planning_time','error_code','trajectory_error_codes']
02582 _slot_types = ['arm_navigation_msgs/RobotTrajectory','arm_navigation_msgs/RobotState','duration','arm_navigation_msgs/ArmNavigationErrorCodes','arm_navigation_msgs/ArmNavigationErrorCodes[]']
02583
02584 def __init__(self, *args, **kwds):
02585 """
02586 Constructor. Any message fields that are implicitly/explicitly
02587 set to None will be assigned a default value. The recommend
02588 use is keyword arguments as this is more robust to future message
02589 changes. You cannot mix in-order arguments and keyword arguments.
02590
02591 The available fields are:
02592 trajectory,robot_state,planning_time,error_code,trajectory_error_codes
02593
02594 :param args: complete set of field values, in .msg order
02595 :param kwds: use keyword arguments corresponding to message field names
02596 to set specific fields.
02597 """
02598 if args or kwds:
02599 super(GetMotionPlanResponse, self).__init__(*args, **kwds)
02600
02601 if self.trajectory is None:
02602 self.trajectory = arm_navigation_msgs.msg.RobotTrajectory()
02603 if self.robot_state is None:
02604 self.robot_state = arm_navigation_msgs.msg.RobotState()
02605 if self.planning_time is None:
02606 self.planning_time = genpy.Duration()
02607 if self.error_code is None:
02608 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02609 if self.trajectory_error_codes is None:
02610 self.trajectory_error_codes = []
02611 else:
02612 self.trajectory = arm_navigation_msgs.msg.RobotTrajectory()
02613 self.robot_state = arm_navigation_msgs.msg.RobotState()
02614 self.planning_time = genpy.Duration()
02615 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02616 self.trajectory_error_codes = []
02617
02618 def _get_types(self):
02619 """
02620 internal API method
02621 """
02622 return self._slot_types
02623
02624 def serialize(self, buff):
02625 """
02626 serialize message into buffer
02627 :param buff: buffer, ``StringIO``
02628 """
02629 try:
02630 _x = self
02631 buff.write(_struct_3I.pack(_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs))
02632 _x = self.trajectory.joint_trajectory.header.frame_id
02633 length = len(_x)
02634 if python3 or type(_x) == unicode:
02635 _x = _x.encode('utf-8')
02636 length = len(_x)
02637 buff.write(struct.pack('<I%ss'%length, length, _x))
02638 length = len(self.trajectory.joint_trajectory.joint_names)
02639 buff.write(_struct_I.pack(length))
02640 for val1 in self.trajectory.joint_trajectory.joint_names:
02641 length = len(val1)
02642 if python3 or type(val1) == unicode:
02643 val1 = val1.encode('utf-8')
02644 length = len(val1)
02645 buff.write(struct.pack('<I%ss'%length, length, val1))
02646 length = len(self.trajectory.joint_trajectory.points)
02647 buff.write(_struct_I.pack(length))
02648 for val1 in self.trajectory.joint_trajectory.points:
02649 length = len(val1.positions)
02650 buff.write(_struct_I.pack(length))
02651 pattern = '<%sd'%length
02652 buff.write(struct.pack(pattern, *val1.positions))
02653 length = len(val1.velocities)
02654 buff.write(_struct_I.pack(length))
02655 pattern = '<%sd'%length
02656 buff.write(struct.pack(pattern, *val1.velocities))
02657 length = len(val1.accelerations)
02658 buff.write(_struct_I.pack(length))
02659 pattern = '<%sd'%length
02660 buff.write(struct.pack(pattern, *val1.accelerations))
02661 _v177 = val1.time_from_start
02662 _x = _v177
02663 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
02664 _x = self
02665 buff.write(_struct_2i.pack(_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs))
02666 length = len(self.trajectory.multi_dof_joint_trajectory.joint_names)
02667 buff.write(_struct_I.pack(length))
02668 for val1 in self.trajectory.multi_dof_joint_trajectory.joint_names:
02669 length = len(val1)
02670 if python3 or type(val1) == unicode:
02671 val1 = val1.encode('utf-8')
02672 length = len(val1)
02673 buff.write(struct.pack('<I%ss'%length, length, val1))
02674 length = len(self.trajectory.multi_dof_joint_trajectory.frame_ids)
02675 buff.write(_struct_I.pack(length))
02676 for val1 in self.trajectory.multi_dof_joint_trajectory.frame_ids:
02677 length = len(val1)
02678 if python3 or type(val1) == unicode:
02679 val1 = val1.encode('utf-8')
02680 length = len(val1)
02681 buff.write(struct.pack('<I%ss'%length, length, val1))
02682 length = len(self.trajectory.multi_dof_joint_trajectory.child_frame_ids)
02683 buff.write(_struct_I.pack(length))
02684 for val1 in self.trajectory.multi_dof_joint_trajectory.child_frame_ids:
02685 length = len(val1)
02686 if python3 or type(val1) == unicode:
02687 val1 = val1.encode('utf-8')
02688 length = len(val1)
02689 buff.write(struct.pack('<I%ss'%length, length, val1))
02690 length = len(self.trajectory.multi_dof_joint_trajectory.points)
02691 buff.write(_struct_I.pack(length))
02692 for val1 in self.trajectory.multi_dof_joint_trajectory.points:
02693 length = len(val1.poses)
02694 buff.write(_struct_I.pack(length))
02695 for val2 in val1.poses:
02696 _v178 = val2.position
02697 _x = _v178
02698 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02699 _v179 = val2.orientation
02700 _x = _v179
02701 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02702 _v180 = val1.time_from_start
02703 _x = _v180
02704 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
02705 _x = self
02706 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
02707 _x = self.robot_state.joint_state.header.frame_id
02708 length = len(_x)
02709 if python3 or type(_x) == unicode:
02710 _x = _x.encode('utf-8')
02711 length = len(_x)
02712 buff.write(struct.pack('<I%ss'%length, length, _x))
02713 length = len(self.robot_state.joint_state.name)
02714 buff.write(_struct_I.pack(length))
02715 for val1 in self.robot_state.joint_state.name:
02716 length = len(val1)
02717 if python3 or type(val1) == unicode:
02718 val1 = val1.encode('utf-8')
02719 length = len(val1)
02720 buff.write(struct.pack('<I%ss'%length, length, val1))
02721 length = len(self.robot_state.joint_state.position)
02722 buff.write(_struct_I.pack(length))
02723 pattern = '<%sd'%length
02724 buff.write(struct.pack(pattern, *self.robot_state.joint_state.position))
02725 length = len(self.robot_state.joint_state.velocity)
02726 buff.write(_struct_I.pack(length))
02727 pattern = '<%sd'%length
02728 buff.write(struct.pack(pattern, *self.robot_state.joint_state.velocity))
02729 length = len(self.robot_state.joint_state.effort)
02730 buff.write(_struct_I.pack(length))
02731 pattern = '<%sd'%length
02732 buff.write(struct.pack(pattern, *self.robot_state.joint_state.effort))
02733 _x = self
02734 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
02735 length = len(self.robot_state.multi_dof_joint_state.joint_names)
02736 buff.write(_struct_I.pack(length))
02737 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
02738 length = len(val1)
02739 if python3 or type(val1) == unicode:
02740 val1 = val1.encode('utf-8')
02741 length = len(val1)
02742 buff.write(struct.pack('<I%ss'%length, length, val1))
02743 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
02744 buff.write(_struct_I.pack(length))
02745 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
02746 length = len(val1)
02747 if python3 or type(val1) == unicode:
02748 val1 = val1.encode('utf-8')
02749 length = len(val1)
02750 buff.write(struct.pack('<I%ss'%length, length, val1))
02751 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
02752 buff.write(_struct_I.pack(length))
02753 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
02754 length = len(val1)
02755 if python3 or type(val1) == unicode:
02756 val1 = val1.encode('utf-8')
02757 length = len(val1)
02758 buff.write(struct.pack('<I%ss'%length, length, val1))
02759 length = len(self.robot_state.multi_dof_joint_state.poses)
02760 buff.write(_struct_I.pack(length))
02761 for val1 in self.robot_state.multi_dof_joint_state.poses:
02762 _v181 = val1.position
02763 _x = _v181
02764 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02765 _v182 = val1.orientation
02766 _x = _v182
02767 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02768 _x = self
02769 buff.write(_struct_3i.pack(_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val))
02770 length = len(self.trajectory_error_codes)
02771 buff.write(_struct_I.pack(length))
02772 for val1 in self.trajectory_error_codes:
02773 buff.write(_struct_i.pack(val1.val))
02774 except struct.error as se: self._check_types(se)
02775 except TypeError as te: self._check_types(te)
02776
02777 def deserialize(self, str):
02778 """
02779 unpack serialized message in str into this message instance
02780 :param str: byte array of serialized message, ``str``
02781 """
02782 try:
02783 if self.trajectory is None:
02784 self.trajectory = arm_navigation_msgs.msg.RobotTrajectory()
02785 if self.robot_state is None:
02786 self.robot_state = arm_navigation_msgs.msg.RobotState()
02787 if self.planning_time is None:
02788 self.planning_time = genpy.Duration()
02789 if self.error_code is None:
02790 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02791 if self.trajectory_error_codes is None:
02792 self.trajectory_error_codes = None
02793 end = 0
02794 _x = self
02795 start = end
02796 end += 12
02797 (_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02798 start = end
02799 end += 4
02800 (length,) = _struct_I.unpack(str[start:end])
02801 start = end
02802 end += length
02803 if python3:
02804 self.trajectory.joint_trajectory.header.frame_id = str[start:end].decode('utf-8')
02805 else:
02806 self.trajectory.joint_trajectory.header.frame_id = str[start:end]
02807 start = end
02808 end += 4
02809 (length,) = _struct_I.unpack(str[start:end])
02810 self.trajectory.joint_trajectory.joint_names = []
02811 for i in range(0, length):
02812 start = end
02813 end += 4
02814 (length,) = _struct_I.unpack(str[start:end])
02815 start = end
02816 end += length
02817 if python3:
02818 val1 = str[start:end].decode('utf-8')
02819 else:
02820 val1 = str[start:end]
02821 self.trajectory.joint_trajectory.joint_names.append(val1)
02822 start = end
02823 end += 4
02824 (length,) = _struct_I.unpack(str[start:end])
02825 self.trajectory.joint_trajectory.points = []
02826 for i in range(0, length):
02827 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
02828 start = end
02829 end += 4
02830 (length,) = _struct_I.unpack(str[start:end])
02831 pattern = '<%sd'%length
02832 start = end
02833 end += struct.calcsize(pattern)
02834 val1.positions = struct.unpack(pattern, str[start:end])
02835 start = end
02836 end += 4
02837 (length,) = _struct_I.unpack(str[start:end])
02838 pattern = '<%sd'%length
02839 start = end
02840 end += struct.calcsize(pattern)
02841 val1.velocities = struct.unpack(pattern, str[start:end])
02842 start = end
02843 end += 4
02844 (length,) = _struct_I.unpack(str[start:end])
02845 pattern = '<%sd'%length
02846 start = end
02847 end += struct.calcsize(pattern)
02848 val1.accelerations = struct.unpack(pattern, str[start:end])
02849 _v183 = val1.time_from_start
02850 _x = _v183
02851 start = end
02852 end += 8
02853 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
02854 self.trajectory.joint_trajectory.points.append(val1)
02855 _x = self
02856 start = end
02857 end += 8
02858 (_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end])
02859 start = end
02860 end += 4
02861 (length,) = _struct_I.unpack(str[start:end])
02862 self.trajectory.multi_dof_joint_trajectory.joint_names = []
02863 for i in range(0, length):
02864 start = end
02865 end += 4
02866 (length,) = _struct_I.unpack(str[start:end])
02867 start = end
02868 end += length
02869 if python3:
02870 val1 = str[start:end].decode('utf-8')
02871 else:
02872 val1 = str[start:end]
02873 self.trajectory.multi_dof_joint_trajectory.joint_names.append(val1)
02874 start = end
02875 end += 4
02876 (length,) = _struct_I.unpack(str[start:end])
02877 self.trajectory.multi_dof_joint_trajectory.frame_ids = []
02878 for i in range(0, length):
02879 start = end
02880 end += 4
02881 (length,) = _struct_I.unpack(str[start:end])
02882 start = end
02883 end += length
02884 if python3:
02885 val1 = str[start:end].decode('utf-8')
02886 else:
02887 val1 = str[start:end]
02888 self.trajectory.multi_dof_joint_trajectory.frame_ids.append(val1)
02889 start = end
02890 end += 4
02891 (length,) = _struct_I.unpack(str[start:end])
02892 self.trajectory.multi_dof_joint_trajectory.child_frame_ids = []
02893 for i in range(0, length):
02894 start = end
02895 end += 4
02896 (length,) = _struct_I.unpack(str[start:end])
02897 start = end
02898 end += length
02899 if python3:
02900 val1 = str[start:end].decode('utf-8')
02901 else:
02902 val1 = str[start:end]
02903 self.trajectory.multi_dof_joint_trajectory.child_frame_ids.append(val1)
02904 start = end
02905 end += 4
02906 (length,) = _struct_I.unpack(str[start:end])
02907 self.trajectory.multi_dof_joint_trajectory.points = []
02908 for i in range(0, length):
02909 val1 = arm_navigation_msgs.msg.MultiDOFJointTrajectoryPoint()
02910 start = end
02911 end += 4
02912 (length,) = _struct_I.unpack(str[start:end])
02913 val1.poses = []
02914 for i in range(0, length):
02915 val2 = geometry_msgs.msg.Pose()
02916 _v184 = val2.position
02917 _x = _v184
02918 start = end
02919 end += 24
02920 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02921 _v185 = val2.orientation
02922 _x = _v185
02923 start = end
02924 end += 32
02925 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02926 val1.poses.append(val2)
02927 _v186 = val1.time_from_start
02928 _x = _v186
02929 start = end
02930 end += 8
02931 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
02932 self.trajectory.multi_dof_joint_trajectory.points.append(val1)
02933 _x = self
02934 start = end
02935 end += 12
02936 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02937 start = end
02938 end += 4
02939 (length,) = _struct_I.unpack(str[start:end])
02940 start = end
02941 end += length
02942 if python3:
02943 self.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
02944 else:
02945 self.robot_state.joint_state.header.frame_id = str[start:end]
02946 start = end
02947 end += 4
02948 (length,) = _struct_I.unpack(str[start:end])
02949 self.robot_state.joint_state.name = []
02950 for i in range(0, length):
02951 start = end
02952 end += 4
02953 (length,) = _struct_I.unpack(str[start:end])
02954 start = end
02955 end += length
02956 if python3:
02957 val1 = str[start:end].decode('utf-8')
02958 else:
02959 val1 = str[start:end]
02960 self.robot_state.joint_state.name.append(val1)
02961 start = end
02962 end += 4
02963 (length,) = _struct_I.unpack(str[start:end])
02964 pattern = '<%sd'%length
02965 start = end
02966 end += struct.calcsize(pattern)
02967 self.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
02968 start = end
02969 end += 4
02970 (length,) = _struct_I.unpack(str[start:end])
02971 pattern = '<%sd'%length
02972 start = end
02973 end += struct.calcsize(pattern)
02974 self.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
02975 start = end
02976 end += 4
02977 (length,) = _struct_I.unpack(str[start:end])
02978 pattern = '<%sd'%length
02979 start = end
02980 end += struct.calcsize(pattern)
02981 self.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
02982 _x = self
02983 start = end
02984 end += 8
02985 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02986 start = end
02987 end += 4
02988 (length,) = _struct_I.unpack(str[start:end])
02989 self.robot_state.multi_dof_joint_state.joint_names = []
02990 for i in range(0, length):
02991 start = end
02992 end += 4
02993 (length,) = _struct_I.unpack(str[start:end])
02994 start = end
02995 end += length
02996 if python3:
02997 val1 = str[start:end].decode('utf-8')
02998 else:
02999 val1 = str[start:end]
03000 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
03001 start = end
03002 end += 4
03003 (length,) = _struct_I.unpack(str[start:end])
03004 self.robot_state.multi_dof_joint_state.frame_ids = []
03005 for i in range(0, length):
03006 start = end
03007 end += 4
03008 (length,) = _struct_I.unpack(str[start:end])
03009 start = end
03010 end += length
03011 if python3:
03012 val1 = str[start:end].decode('utf-8')
03013 else:
03014 val1 = str[start:end]
03015 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03016 start = end
03017 end += 4
03018 (length,) = _struct_I.unpack(str[start:end])
03019 self.robot_state.multi_dof_joint_state.child_frame_ids = []
03020 for i in range(0, length):
03021 start = end
03022 end += 4
03023 (length,) = _struct_I.unpack(str[start:end])
03024 start = end
03025 end += length
03026 if python3:
03027 val1 = str[start:end].decode('utf-8')
03028 else:
03029 val1 = str[start:end]
03030 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03031 start = end
03032 end += 4
03033 (length,) = _struct_I.unpack(str[start:end])
03034 self.robot_state.multi_dof_joint_state.poses = []
03035 for i in range(0, length):
03036 val1 = geometry_msgs.msg.Pose()
03037 _v187 = val1.position
03038 _x = _v187
03039 start = end
03040 end += 24
03041 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03042 _v188 = val1.orientation
03043 _x = _v188
03044 start = end
03045 end += 32
03046 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03047 self.robot_state.multi_dof_joint_state.poses.append(val1)
03048 _x = self
03049 start = end
03050 end += 12
03051 (_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val,) = _struct_3i.unpack(str[start:end])
03052 start = end
03053 end += 4
03054 (length,) = _struct_I.unpack(str[start:end])
03055 self.trajectory_error_codes = []
03056 for i in range(0, length):
03057 val1 = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
03058 start = end
03059 end += 4
03060 (val1.val,) = _struct_i.unpack(str[start:end])
03061 self.trajectory_error_codes.append(val1)
03062 self.planning_time.canon()
03063 return self
03064 except struct.error as e:
03065 raise genpy.DeserializationError(e)
03066
03067
03068 def serialize_numpy(self, buff, numpy):
03069 """
03070 serialize message with numpy array types into buffer
03071 :param buff: buffer, ``StringIO``
03072 :param numpy: numpy python module
03073 """
03074 try:
03075 _x = self
03076 buff.write(_struct_3I.pack(_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs))
03077 _x = self.trajectory.joint_trajectory.header.frame_id
03078 length = len(_x)
03079 if python3 or type(_x) == unicode:
03080 _x = _x.encode('utf-8')
03081 length = len(_x)
03082 buff.write(struct.pack('<I%ss'%length, length, _x))
03083 length = len(self.trajectory.joint_trajectory.joint_names)
03084 buff.write(_struct_I.pack(length))
03085 for val1 in self.trajectory.joint_trajectory.joint_names:
03086 length = len(val1)
03087 if python3 or type(val1) == unicode:
03088 val1 = val1.encode('utf-8')
03089 length = len(val1)
03090 buff.write(struct.pack('<I%ss'%length, length, val1))
03091 length = len(self.trajectory.joint_trajectory.points)
03092 buff.write(_struct_I.pack(length))
03093 for val1 in self.trajectory.joint_trajectory.points:
03094 length = len(val1.positions)
03095 buff.write(_struct_I.pack(length))
03096 pattern = '<%sd'%length
03097 buff.write(val1.positions.tostring())
03098 length = len(val1.velocities)
03099 buff.write(_struct_I.pack(length))
03100 pattern = '<%sd'%length
03101 buff.write(val1.velocities.tostring())
03102 length = len(val1.accelerations)
03103 buff.write(_struct_I.pack(length))
03104 pattern = '<%sd'%length
03105 buff.write(val1.accelerations.tostring())
03106 _v189 = val1.time_from_start
03107 _x = _v189
03108 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
03109 _x = self
03110 buff.write(_struct_2i.pack(_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs))
03111 length = len(self.trajectory.multi_dof_joint_trajectory.joint_names)
03112 buff.write(_struct_I.pack(length))
03113 for val1 in self.trajectory.multi_dof_joint_trajectory.joint_names:
03114 length = len(val1)
03115 if python3 or type(val1) == unicode:
03116 val1 = val1.encode('utf-8')
03117 length = len(val1)
03118 buff.write(struct.pack('<I%ss'%length, length, val1))
03119 length = len(self.trajectory.multi_dof_joint_trajectory.frame_ids)
03120 buff.write(_struct_I.pack(length))
03121 for val1 in self.trajectory.multi_dof_joint_trajectory.frame_ids:
03122 length = len(val1)
03123 if python3 or type(val1) == unicode:
03124 val1 = val1.encode('utf-8')
03125 length = len(val1)
03126 buff.write(struct.pack('<I%ss'%length, length, val1))
03127 length = len(self.trajectory.multi_dof_joint_trajectory.child_frame_ids)
03128 buff.write(_struct_I.pack(length))
03129 for val1 in self.trajectory.multi_dof_joint_trajectory.child_frame_ids:
03130 length = len(val1)
03131 if python3 or type(val1) == unicode:
03132 val1 = val1.encode('utf-8')
03133 length = len(val1)
03134 buff.write(struct.pack('<I%ss'%length, length, val1))
03135 length = len(self.trajectory.multi_dof_joint_trajectory.points)
03136 buff.write(_struct_I.pack(length))
03137 for val1 in self.trajectory.multi_dof_joint_trajectory.points:
03138 length = len(val1.poses)
03139 buff.write(_struct_I.pack(length))
03140 for val2 in val1.poses:
03141 _v190 = val2.position
03142 _x = _v190
03143 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03144 _v191 = val2.orientation
03145 _x = _v191
03146 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03147 _v192 = val1.time_from_start
03148 _x = _v192
03149 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
03150 _x = self
03151 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
03152 _x = self.robot_state.joint_state.header.frame_id
03153 length = len(_x)
03154 if python3 or type(_x) == unicode:
03155 _x = _x.encode('utf-8')
03156 length = len(_x)
03157 buff.write(struct.pack('<I%ss'%length, length, _x))
03158 length = len(self.robot_state.joint_state.name)
03159 buff.write(_struct_I.pack(length))
03160 for val1 in self.robot_state.joint_state.name:
03161 length = len(val1)
03162 if python3 or type(val1) == unicode:
03163 val1 = val1.encode('utf-8')
03164 length = len(val1)
03165 buff.write(struct.pack('<I%ss'%length, length, val1))
03166 length = len(self.robot_state.joint_state.position)
03167 buff.write(_struct_I.pack(length))
03168 pattern = '<%sd'%length
03169 buff.write(self.robot_state.joint_state.position.tostring())
03170 length = len(self.robot_state.joint_state.velocity)
03171 buff.write(_struct_I.pack(length))
03172 pattern = '<%sd'%length
03173 buff.write(self.robot_state.joint_state.velocity.tostring())
03174 length = len(self.robot_state.joint_state.effort)
03175 buff.write(_struct_I.pack(length))
03176 pattern = '<%sd'%length
03177 buff.write(self.robot_state.joint_state.effort.tostring())
03178 _x = self
03179 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
03180 length = len(self.robot_state.multi_dof_joint_state.joint_names)
03181 buff.write(_struct_I.pack(length))
03182 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
03183 length = len(val1)
03184 if python3 or type(val1) == unicode:
03185 val1 = val1.encode('utf-8')
03186 length = len(val1)
03187 buff.write(struct.pack('<I%ss'%length, length, val1))
03188 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
03189 buff.write(_struct_I.pack(length))
03190 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
03191 length = len(val1)
03192 if python3 or type(val1) == unicode:
03193 val1 = val1.encode('utf-8')
03194 length = len(val1)
03195 buff.write(struct.pack('<I%ss'%length, length, val1))
03196 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
03197 buff.write(_struct_I.pack(length))
03198 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
03199 length = len(val1)
03200 if python3 or type(val1) == unicode:
03201 val1 = val1.encode('utf-8')
03202 length = len(val1)
03203 buff.write(struct.pack('<I%ss'%length, length, val1))
03204 length = len(self.robot_state.multi_dof_joint_state.poses)
03205 buff.write(_struct_I.pack(length))
03206 for val1 in self.robot_state.multi_dof_joint_state.poses:
03207 _v193 = val1.position
03208 _x = _v193
03209 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03210 _v194 = val1.orientation
03211 _x = _v194
03212 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03213 _x = self
03214 buff.write(_struct_3i.pack(_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val))
03215 length = len(self.trajectory_error_codes)
03216 buff.write(_struct_I.pack(length))
03217 for val1 in self.trajectory_error_codes:
03218 buff.write(_struct_i.pack(val1.val))
03219 except struct.error as se: self._check_types(se)
03220 except TypeError as te: self._check_types(te)
03221
03222 def deserialize_numpy(self, str, numpy):
03223 """
03224 unpack serialized message in str into this message instance using numpy for array types
03225 :param str: byte array of serialized message, ``str``
03226 :param numpy: numpy python module
03227 """
03228 try:
03229 if self.trajectory is None:
03230 self.trajectory = arm_navigation_msgs.msg.RobotTrajectory()
03231 if self.robot_state is None:
03232 self.robot_state = arm_navigation_msgs.msg.RobotState()
03233 if self.planning_time is None:
03234 self.planning_time = genpy.Duration()
03235 if self.error_code is None:
03236 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
03237 if self.trajectory_error_codes is None:
03238 self.trajectory_error_codes = None
03239 end = 0
03240 _x = self
03241 start = end
03242 end += 12
03243 (_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03244 start = end
03245 end += 4
03246 (length,) = _struct_I.unpack(str[start:end])
03247 start = end
03248 end += length
03249 if python3:
03250 self.trajectory.joint_trajectory.header.frame_id = str[start:end].decode('utf-8')
03251 else:
03252 self.trajectory.joint_trajectory.header.frame_id = str[start:end]
03253 start = end
03254 end += 4
03255 (length,) = _struct_I.unpack(str[start:end])
03256 self.trajectory.joint_trajectory.joint_names = []
03257 for i in range(0, length):
03258 start = end
03259 end += 4
03260 (length,) = _struct_I.unpack(str[start:end])
03261 start = end
03262 end += length
03263 if python3:
03264 val1 = str[start:end].decode('utf-8')
03265 else:
03266 val1 = str[start:end]
03267 self.trajectory.joint_trajectory.joint_names.append(val1)
03268 start = end
03269 end += 4
03270 (length,) = _struct_I.unpack(str[start:end])
03271 self.trajectory.joint_trajectory.points = []
03272 for i in range(0, length):
03273 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
03274 start = end
03275 end += 4
03276 (length,) = _struct_I.unpack(str[start:end])
03277 pattern = '<%sd'%length
03278 start = end
03279 end += struct.calcsize(pattern)
03280 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03281 start = end
03282 end += 4
03283 (length,) = _struct_I.unpack(str[start:end])
03284 pattern = '<%sd'%length
03285 start = end
03286 end += struct.calcsize(pattern)
03287 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03288 start = end
03289 end += 4
03290 (length,) = _struct_I.unpack(str[start:end])
03291 pattern = '<%sd'%length
03292 start = end
03293 end += struct.calcsize(pattern)
03294 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03295 _v195 = val1.time_from_start
03296 _x = _v195
03297 start = end
03298 end += 8
03299 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
03300 self.trajectory.joint_trajectory.points.append(val1)
03301 _x = self
03302 start = end
03303 end += 8
03304 (_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end])
03305 start = end
03306 end += 4
03307 (length,) = _struct_I.unpack(str[start:end])
03308 self.trajectory.multi_dof_joint_trajectory.joint_names = []
03309 for i in range(0, length):
03310 start = end
03311 end += 4
03312 (length,) = _struct_I.unpack(str[start:end])
03313 start = end
03314 end += length
03315 if python3:
03316 val1 = str[start:end].decode('utf-8')
03317 else:
03318 val1 = str[start:end]
03319 self.trajectory.multi_dof_joint_trajectory.joint_names.append(val1)
03320 start = end
03321 end += 4
03322 (length,) = _struct_I.unpack(str[start:end])
03323 self.trajectory.multi_dof_joint_trajectory.frame_ids = []
03324 for i in range(0, length):
03325 start = end
03326 end += 4
03327 (length,) = _struct_I.unpack(str[start:end])
03328 start = end
03329 end += length
03330 if python3:
03331 val1 = str[start:end].decode('utf-8')
03332 else:
03333 val1 = str[start:end]
03334 self.trajectory.multi_dof_joint_trajectory.frame_ids.append(val1)
03335 start = end
03336 end += 4
03337 (length,) = _struct_I.unpack(str[start:end])
03338 self.trajectory.multi_dof_joint_trajectory.child_frame_ids = []
03339 for i in range(0, length):
03340 start = end
03341 end += 4
03342 (length,) = _struct_I.unpack(str[start:end])
03343 start = end
03344 end += length
03345 if python3:
03346 val1 = str[start:end].decode('utf-8')
03347 else:
03348 val1 = str[start:end]
03349 self.trajectory.multi_dof_joint_trajectory.child_frame_ids.append(val1)
03350 start = end
03351 end += 4
03352 (length,) = _struct_I.unpack(str[start:end])
03353 self.trajectory.multi_dof_joint_trajectory.points = []
03354 for i in range(0, length):
03355 val1 = arm_navigation_msgs.msg.MultiDOFJointTrajectoryPoint()
03356 start = end
03357 end += 4
03358 (length,) = _struct_I.unpack(str[start:end])
03359 val1.poses = []
03360 for i in range(0, length):
03361 val2 = geometry_msgs.msg.Pose()
03362 _v196 = val2.position
03363 _x = _v196
03364 start = end
03365 end += 24
03366 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03367 _v197 = val2.orientation
03368 _x = _v197
03369 start = end
03370 end += 32
03371 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03372 val1.poses.append(val2)
03373 _v198 = val1.time_from_start
03374 _x = _v198
03375 start = end
03376 end += 8
03377 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
03378 self.trajectory.multi_dof_joint_trajectory.points.append(val1)
03379 _x = self
03380 start = end
03381 end += 12
03382 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03383 start = end
03384 end += 4
03385 (length,) = _struct_I.unpack(str[start:end])
03386 start = end
03387 end += length
03388 if python3:
03389 self.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
03390 else:
03391 self.robot_state.joint_state.header.frame_id = str[start:end]
03392 start = end
03393 end += 4
03394 (length,) = _struct_I.unpack(str[start:end])
03395 self.robot_state.joint_state.name = []
03396 for i in range(0, length):
03397 start = end
03398 end += 4
03399 (length,) = _struct_I.unpack(str[start:end])
03400 start = end
03401 end += length
03402 if python3:
03403 val1 = str[start:end].decode('utf-8')
03404 else:
03405 val1 = str[start:end]
03406 self.robot_state.joint_state.name.append(val1)
03407 start = end
03408 end += 4
03409 (length,) = _struct_I.unpack(str[start:end])
03410 pattern = '<%sd'%length
03411 start = end
03412 end += struct.calcsize(pattern)
03413 self.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03414 start = end
03415 end += 4
03416 (length,) = _struct_I.unpack(str[start:end])
03417 pattern = '<%sd'%length
03418 start = end
03419 end += struct.calcsize(pattern)
03420 self.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03421 start = end
03422 end += 4
03423 (length,) = _struct_I.unpack(str[start:end])
03424 pattern = '<%sd'%length
03425 start = end
03426 end += struct.calcsize(pattern)
03427 self.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03428 _x = self
03429 start = end
03430 end += 8
03431 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03432 start = end
03433 end += 4
03434 (length,) = _struct_I.unpack(str[start:end])
03435 self.robot_state.multi_dof_joint_state.joint_names = []
03436 for i in range(0, length):
03437 start = end
03438 end += 4
03439 (length,) = _struct_I.unpack(str[start:end])
03440 start = end
03441 end += length
03442 if python3:
03443 val1 = str[start:end].decode('utf-8')
03444 else:
03445 val1 = str[start:end]
03446 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
03447 start = end
03448 end += 4
03449 (length,) = _struct_I.unpack(str[start:end])
03450 self.robot_state.multi_dof_joint_state.frame_ids = []
03451 for i in range(0, length):
03452 start = end
03453 end += 4
03454 (length,) = _struct_I.unpack(str[start:end])
03455 start = end
03456 end += length
03457 if python3:
03458 val1 = str[start:end].decode('utf-8')
03459 else:
03460 val1 = str[start:end]
03461 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03462 start = end
03463 end += 4
03464 (length,) = _struct_I.unpack(str[start:end])
03465 self.robot_state.multi_dof_joint_state.child_frame_ids = []
03466 for i in range(0, length):
03467 start = end
03468 end += 4
03469 (length,) = _struct_I.unpack(str[start:end])
03470 start = end
03471 end += length
03472 if python3:
03473 val1 = str[start:end].decode('utf-8')
03474 else:
03475 val1 = str[start:end]
03476 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03477 start = end
03478 end += 4
03479 (length,) = _struct_I.unpack(str[start:end])
03480 self.robot_state.multi_dof_joint_state.poses = []
03481 for i in range(0, length):
03482 val1 = geometry_msgs.msg.Pose()
03483 _v199 = val1.position
03484 _x = _v199
03485 start = end
03486 end += 24
03487 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03488 _v200 = val1.orientation
03489 _x = _v200
03490 start = end
03491 end += 32
03492 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03493 self.robot_state.multi_dof_joint_state.poses.append(val1)
03494 _x = self
03495 start = end
03496 end += 12
03497 (_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val,) = _struct_3i.unpack(str[start:end])
03498 start = end
03499 end += 4
03500 (length,) = _struct_I.unpack(str[start:end])
03501 self.trajectory_error_codes = []
03502 for i in range(0, length):
03503 val1 = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
03504 start = end
03505 end += 4
03506 (val1.val,) = _struct_i.unpack(str[start:end])
03507 self.trajectory_error_codes.append(val1)
03508 self.planning_time.canon()
03509 return self
03510 except struct.error as e:
03511 raise genpy.DeserializationError(e)
03512
03513 _struct_I = genpy.struct_I
03514 _struct_i = struct.Struct("<i")
03515 _struct_3i = struct.Struct("<3i")
03516 _struct_2I = struct.Struct("<2I")
03517 _struct_3I = struct.Struct("<3I")
03518 _struct_4d = struct.Struct("<4d")
03519 _struct_2i = struct.Struct("<2i")
03520 _struct_3d = struct.Struct("<3d")
03521 class GetMotionPlan(object):
03522 _type = 'arm_navigation_msgs/GetMotionPlan'
03523 _md5sum = 'e7f04013c167d0703692fec8a86b22ef'
03524 _request_class = GetMotionPlanRequest
03525 _response_class = GetMotionPlanResponse