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