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