_IK.py
Go to the documentation of this file.
00001 """autogenerated by genpy from orrosplanning/IKRequest.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 geometry_msgs.msg
00008 import std_msgs.msg
00009 import sensor_msgs.msg
00010 
00011 class IKRequest(genpy.Message):
00012   _md5sum = "6c7c32c8815dff364106532bc2227956"
00013   _type = "orrosplanning/IKRequest"
00014   _has_header = False #flag to mark the presence of a Header object
00015   _full_text = """
00016 
00017 string manip_name
00018 
00019 
00020 
00021 string iktype
00022 
00023 
00024 sensor_msgs/JointState joint_state
00025 
00026 
00027 geometry_msgs/PoseStamped pose_stamped
00028 
00029 
00030 int32 filteroptions
00031 
00032 
00033 int32 IGNORE_ENVIRONMENT_COLLISIONS=1
00034 int32 IGNORE_SELF_COLLISIONS=2
00035 int32 IGNORE_JOINT_LIMITS=4
00036 int32 RETURN_CLOSEST_SOLUTION=8
00037 int32 RETURN_ALL_SOLUTIONS=16
00038 
00039 
00040 ================================================================================
00041 MSG: sensor_msgs/JointState
00042 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00043 #
00044 # The state of each joint (revolute or prismatic) is defined by:
00045 #  * the position of the joint (rad or m),
00046 #  * the velocity of the joint (rad/s or m/s) and 
00047 #  * the effort that is applied in the joint (Nm or N).
00048 #
00049 # Each joint is uniquely identified by its name
00050 # The header specifies the time at which the joint states were recorded. All the joint states
00051 # in one message have to be recorded at the same time.
00052 #
00053 # This message consists of a multiple arrays, one for each part of the joint state. 
00054 # The goal is to make each of the fields optional. When e.g. your joints have no
00055 # effort associated with them, you can leave the effort array empty. 
00056 #
00057 # All arrays in this message should have the same size, or be empty.
00058 # This is the only way to uniquely associate the joint name with the correct
00059 # states.
00060 
00061 
00062 Header header
00063 
00064 string[] name
00065 float64[] position
00066 float64[] velocity
00067 float64[] effort
00068 
00069 ================================================================================
00070 MSG: std_msgs/Header
00071 # Standard metadata for higher-level stamped data types.
00072 # This is generally used to communicate timestamped data 
00073 # in a particular coordinate frame.
00074 # 
00075 # sequence ID: consecutively increasing ID 
00076 uint32 seq
00077 #Two-integer timestamp that is expressed as:
00078 # * stamp.secs: seconds (stamp_secs) since epoch
00079 # * stamp.nsecs: nanoseconds since stamp_secs
00080 # time-handling sugar is provided by the client library
00081 time stamp
00082 #Frame this data is associated with
00083 # 0: no frame
00084 # 1: global frame
00085 string frame_id
00086 
00087 ================================================================================
00088 MSG: geometry_msgs/PoseStamped
00089 # A Pose with reference coordinate frame and timestamp
00090 Header header
00091 Pose pose
00092 
00093 ================================================================================
00094 MSG: geometry_msgs/Pose
00095 # A representation of pose in free space, composed of postion and orientation. 
00096 Point position
00097 Quaternion orientation
00098 
00099 ================================================================================
00100 MSG: geometry_msgs/Point
00101 # This contains the position of a point in free space
00102 float64 x
00103 float64 y
00104 float64 z
00105 
00106 ================================================================================
00107 MSG: geometry_msgs/Quaternion
00108 # This represents an orientation in free space in quaternion form.
00109 
00110 float64 x
00111 float64 y
00112 float64 z
00113 float64 w
00114 
00115 """
00116   # Pseudo-constants
00117   IGNORE_ENVIRONMENT_COLLISIONS = 1
00118   IGNORE_SELF_COLLISIONS = 2
00119   IGNORE_JOINT_LIMITS = 4
00120   RETURN_CLOSEST_SOLUTION = 8
00121   RETURN_ALL_SOLUTIONS = 16
00122 
00123   __slots__ = ['manip_name','iktype','joint_state','pose_stamped','filteroptions']
00124   _slot_types = ['string','string','sensor_msgs/JointState','geometry_msgs/PoseStamped','int32']
00125 
00126   def __init__(self, *args, **kwds):
00127     """
00128     Constructor. Any message fields that are implicitly/explicitly
00129     set to None will be assigned a default value. The recommend
00130     use is keyword arguments as this is more robust to future message
00131     changes.  You cannot mix in-order arguments and keyword arguments.
00132 
00133     The available fields are:
00134        manip_name,iktype,joint_state,pose_stamped,filteroptions
00135 
00136     :param args: complete set of field values, in .msg order
00137     :param kwds: use keyword arguments corresponding to message field names
00138     to set specific fields.
00139     """
00140     if args or kwds:
00141       super(IKRequest, self).__init__(*args, **kwds)
00142       #message fields cannot be None, assign default values for those that are
00143       if self.manip_name is None:
00144         self.manip_name = ''
00145       if self.iktype is None:
00146         self.iktype = ''
00147       if self.joint_state is None:
00148         self.joint_state = sensor_msgs.msg.JointState()
00149       if self.pose_stamped is None:
00150         self.pose_stamped = geometry_msgs.msg.PoseStamped()
00151       if self.filteroptions is None:
00152         self.filteroptions = 0
00153     else:
00154       self.manip_name = ''
00155       self.iktype = ''
00156       self.joint_state = sensor_msgs.msg.JointState()
00157       self.pose_stamped = geometry_msgs.msg.PoseStamped()
00158       self.filteroptions = 0
00159 
00160   def _get_types(self):
00161     """
00162     internal API method
00163     """
00164     return self._slot_types
00165 
00166   def serialize(self, buff):
00167     """
00168     serialize message into buffer
00169     :param buff: buffer, ``StringIO``
00170     """
00171     try:
00172       _x = self.manip_name
00173       length = len(_x)
00174       if python3 or type(_x) == unicode:
00175         _x = _x.encode('utf-8')
00176         length = len(_x)
00177       buff.write(struct.pack('<I%ss'%length, length, _x))
00178       _x = self.iktype
00179       length = len(_x)
00180       if python3 or type(_x) == unicode:
00181         _x = _x.encode('utf-8')
00182         length = len(_x)
00183       buff.write(struct.pack('<I%ss'%length, length, _x))
00184       _x = self
00185       buff.write(_struct_3I.pack(_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs))
00186       _x = self.joint_state.header.frame_id
00187       length = len(_x)
00188       if python3 or type(_x) == unicode:
00189         _x = _x.encode('utf-8')
00190         length = len(_x)
00191       buff.write(struct.pack('<I%ss'%length, length, _x))
00192       length = len(self.joint_state.name)
00193       buff.write(_struct_I.pack(length))
00194       for val1 in self.joint_state.name:
00195         length = len(val1)
00196         if python3 or type(val1) == unicode:
00197           val1 = val1.encode('utf-8')
00198           length = len(val1)
00199         buff.write(struct.pack('<I%ss'%length, length, val1))
00200       length = len(self.joint_state.position)
00201       buff.write(_struct_I.pack(length))
00202       pattern = '<%sd'%length
00203       buff.write(struct.pack(pattern, *self.joint_state.position))
00204       length = len(self.joint_state.velocity)
00205       buff.write(_struct_I.pack(length))
00206       pattern = '<%sd'%length
00207       buff.write(struct.pack(pattern, *self.joint_state.velocity))
00208       length = len(self.joint_state.effort)
00209       buff.write(_struct_I.pack(length))
00210       pattern = '<%sd'%length
00211       buff.write(struct.pack(pattern, *self.joint_state.effort))
00212       _x = self
00213       buff.write(_struct_3I.pack(_x.pose_stamped.header.seq, _x.pose_stamped.header.stamp.secs, _x.pose_stamped.header.stamp.nsecs))
00214       _x = self.pose_stamped.header.frame_id
00215       length = len(_x)
00216       if python3 or type(_x) == unicode:
00217         _x = _x.encode('utf-8')
00218         length = len(_x)
00219       buff.write(struct.pack('<I%ss'%length, length, _x))
00220       _x = self
00221       buff.write(_struct_7di.pack(_x.pose_stamped.pose.position.x, _x.pose_stamped.pose.position.y, _x.pose_stamped.pose.position.z, _x.pose_stamped.pose.orientation.x, _x.pose_stamped.pose.orientation.y, _x.pose_stamped.pose.orientation.z, _x.pose_stamped.pose.orientation.w, _x.filteroptions))
00222     except struct.error as se: self._check_types(se)
00223     except TypeError as te: self._check_types(te)
00224 
00225   def deserialize(self, str):
00226     """
00227     unpack serialized message in str into this message instance
00228     :param str: byte array of serialized message, ``str``
00229     """
00230     try:
00231       if self.joint_state is None:
00232         self.joint_state = sensor_msgs.msg.JointState()
00233       if self.pose_stamped is None:
00234         self.pose_stamped = geometry_msgs.msg.PoseStamped()
00235       end = 0
00236       start = end
00237       end += 4
00238       (length,) = _struct_I.unpack(str[start:end])
00239       start = end
00240       end += length
00241       if python3:
00242         self.manip_name = str[start:end].decode('utf-8')
00243       else:
00244         self.manip_name = str[start:end]
00245       start = end
00246       end += 4
00247       (length,) = _struct_I.unpack(str[start:end])
00248       start = end
00249       end += length
00250       if python3:
00251         self.iktype = str[start:end].decode('utf-8')
00252       else:
00253         self.iktype = str[start:end]
00254       _x = self
00255       start = end
00256       end += 12
00257       (_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00258       start = end
00259       end += 4
00260       (length,) = _struct_I.unpack(str[start:end])
00261       start = end
00262       end += length
00263       if python3:
00264         self.joint_state.header.frame_id = str[start:end].decode('utf-8')
00265       else:
00266         self.joint_state.header.frame_id = str[start:end]
00267       start = end
00268       end += 4
00269       (length,) = _struct_I.unpack(str[start:end])
00270       self.joint_state.name = []
00271       for i in range(0, length):
00272         start = end
00273         end += 4
00274         (length,) = _struct_I.unpack(str[start:end])
00275         start = end
00276         end += length
00277         if python3:
00278           val1 = str[start:end].decode('utf-8')
00279         else:
00280           val1 = str[start:end]
00281         self.joint_state.name.append(val1)
00282       start = end
00283       end += 4
00284       (length,) = _struct_I.unpack(str[start:end])
00285       pattern = '<%sd'%length
00286       start = end
00287       end += struct.calcsize(pattern)
00288       self.joint_state.position = struct.unpack(pattern, str[start:end])
00289       start = end
00290       end += 4
00291       (length,) = _struct_I.unpack(str[start:end])
00292       pattern = '<%sd'%length
00293       start = end
00294       end += struct.calcsize(pattern)
00295       self.joint_state.velocity = struct.unpack(pattern, str[start:end])
00296       start = end
00297       end += 4
00298       (length,) = _struct_I.unpack(str[start:end])
00299       pattern = '<%sd'%length
00300       start = end
00301       end += struct.calcsize(pattern)
00302       self.joint_state.effort = struct.unpack(pattern, str[start:end])
00303       _x = self
00304       start = end
00305       end += 12
00306       (_x.pose_stamped.header.seq, _x.pose_stamped.header.stamp.secs, _x.pose_stamped.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00307       start = end
00308       end += 4
00309       (length,) = _struct_I.unpack(str[start:end])
00310       start = end
00311       end += length
00312       if python3:
00313         self.pose_stamped.header.frame_id = str[start:end].decode('utf-8')
00314       else:
00315         self.pose_stamped.header.frame_id = str[start:end]
00316       _x = self
00317       start = end
00318       end += 60
00319       (_x.pose_stamped.pose.position.x, _x.pose_stamped.pose.position.y, _x.pose_stamped.pose.position.z, _x.pose_stamped.pose.orientation.x, _x.pose_stamped.pose.orientation.y, _x.pose_stamped.pose.orientation.z, _x.pose_stamped.pose.orientation.w, _x.filteroptions,) = _struct_7di.unpack(str[start:end])
00320       return self
00321     except struct.error as e:
00322       raise genpy.DeserializationError(e) #most likely buffer underfill
00323 
00324 
00325   def serialize_numpy(self, buff, numpy):
00326     """
00327     serialize message with numpy array types into buffer
00328     :param buff: buffer, ``StringIO``
00329     :param numpy: numpy python module
00330     """
00331     try:
00332       _x = self.manip_name
00333       length = len(_x)
00334       if python3 or type(_x) == unicode:
00335         _x = _x.encode('utf-8')
00336         length = len(_x)
00337       buff.write(struct.pack('<I%ss'%length, length, _x))
00338       _x = self.iktype
00339       length = len(_x)
00340       if python3 or type(_x) == unicode:
00341         _x = _x.encode('utf-8')
00342         length = len(_x)
00343       buff.write(struct.pack('<I%ss'%length, length, _x))
00344       _x = self
00345       buff.write(_struct_3I.pack(_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs))
00346       _x = self.joint_state.header.frame_id
00347       length = len(_x)
00348       if python3 or type(_x) == unicode:
00349         _x = _x.encode('utf-8')
00350         length = len(_x)
00351       buff.write(struct.pack('<I%ss'%length, length, _x))
00352       length = len(self.joint_state.name)
00353       buff.write(_struct_I.pack(length))
00354       for val1 in self.joint_state.name:
00355         length = len(val1)
00356         if python3 or type(val1) == unicode:
00357           val1 = val1.encode('utf-8')
00358           length = len(val1)
00359         buff.write(struct.pack('<I%ss'%length, length, val1))
00360       length = len(self.joint_state.position)
00361       buff.write(_struct_I.pack(length))
00362       pattern = '<%sd'%length
00363       buff.write(self.joint_state.position.tostring())
00364       length = len(self.joint_state.velocity)
00365       buff.write(_struct_I.pack(length))
00366       pattern = '<%sd'%length
00367       buff.write(self.joint_state.velocity.tostring())
00368       length = len(self.joint_state.effort)
00369       buff.write(_struct_I.pack(length))
00370       pattern = '<%sd'%length
00371       buff.write(self.joint_state.effort.tostring())
00372       _x = self
00373       buff.write(_struct_3I.pack(_x.pose_stamped.header.seq, _x.pose_stamped.header.stamp.secs, _x.pose_stamped.header.stamp.nsecs))
00374       _x = self.pose_stamped.header.frame_id
00375       length = len(_x)
00376       if python3 or type(_x) == unicode:
00377         _x = _x.encode('utf-8')
00378         length = len(_x)
00379       buff.write(struct.pack('<I%ss'%length, length, _x))
00380       _x = self
00381       buff.write(_struct_7di.pack(_x.pose_stamped.pose.position.x, _x.pose_stamped.pose.position.y, _x.pose_stamped.pose.position.z, _x.pose_stamped.pose.orientation.x, _x.pose_stamped.pose.orientation.y, _x.pose_stamped.pose.orientation.z, _x.pose_stamped.pose.orientation.w, _x.filteroptions))
00382     except struct.error as se: self._check_types(se)
00383     except TypeError as te: self._check_types(te)
00384 
00385   def deserialize_numpy(self, str, numpy):
00386     """
00387     unpack serialized message in str into this message instance using numpy for array types
00388     :param str: byte array of serialized message, ``str``
00389     :param numpy: numpy python module
00390     """
00391     try:
00392       if self.joint_state is None:
00393         self.joint_state = sensor_msgs.msg.JointState()
00394       if self.pose_stamped is None:
00395         self.pose_stamped = geometry_msgs.msg.PoseStamped()
00396       end = 0
00397       start = end
00398       end += 4
00399       (length,) = _struct_I.unpack(str[start:end])
00400       start = end
00401       end += length
00402       if python3:
00403         self.manip_name = str[start:end].decode('utf-8')
00404       else:
00405         self.manip_name = str[start:end]
00406       start = end
00407       end += 4
00408       (length,) = _struct_I.unpack(str[start:end])
00409       start = end
00410       end += length
00411       if python3:
00412         self.iktype = str[start:end].decode('utf-8')
00413       else:
00414         self.iktype = str[start:end]
00415       _x = self
00416       start = end
00417       end += 12
00418       (_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00419       start = end
00420       end += 4
00421       (length,) = _struct_I.unpack(str[start:end])
00422       start = end
00423       end += length
00424       if python3:
00425         self.joint_state.header.frame_id = str[start:end].decode('utf-8')
00426       else:
00427         self.joint_state.header.frame_id = str[start:end]
00428       start = end
00429       end += 4
00430       (length,) = _struct_I.unpack(str[start:end])
00431       self.joint_state.name = []
00432       for i in range(0, length):
00433         start = end
00434         end += 4
00435         (length,) = _struct_I.unpack(str[start:end])
00436         start = end
00437         end += length
00438         if python3:
00439           val1 = str[start:end].decode('utf-8')
00440         else:
00441           val1 = str[start:end]
00442         self.joint_state.name.append(val1)
00443       start = end
00444       end += 4
00445       (length,) = _struct_I.unpack(str[start:end])
00446       pattern = '<%sd'%length
00447       start = end
00448       end += struct.calcsize(pattern)
00449       self.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00450       start = end
00451       end += 4
00452       (length,) = _struct_I.unpack(str[start:end])
00453       pattern = '<%sd'%length
00454       start = end
00455       end += struct.calcsize(pattern)
00456       self.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00457       start = end
00458       end += 4
00459       (length,) = _struct_I.unpack(str[start:end])
00460       pattern = '<%sd'%length
00461       start = end
00462       end += struct.calcsize(pattern)
00463       self.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00464       _x = self
00465       start = end
00466       end += 12
00467       (_x.pose_stamped.header.seq, _x.pose_stamped.header.stamp.secs, _x.pose_stamped.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00468       start = end
00469       end += 4
00470       (length,) = _struct_I.unpack(str[start:end])
00471       start = end
00472       end += length
00473       if python3:
00474         self.pose_stamped.header.frame_id = str[start:end].decode('utf-8')
00475       else:
00476         self.pose_stamped.header.frame_id = str[start:end]
00477       _x = self
00478       start = end
00479       end += 60
00480       (_x.pose_stamped.pose.position.x, _x.pose_stamped.pose.position.y, _x.pose_stamped.pose.position.z, _x.pose_stamped.pose.orientation.x, _x.pose_stamped.pose.orientation.y, _x.pose_stamped.pose.orientation.z, _x.pose_stamped.pose.orientation.w, _x.filteroptions,) = _struct_7di.unpack(str[start:end])
00481       return self
00482     except struct.error as e:
00483       raise genpy.DeserializationError(e) #most likely buffer underfill
00484 
00485 _struct_I = genpy.struct_I
00486 _struct_7di = struct.Struct("<7di")
00487 _struct_3I = struct.Struct("<3I")
00488 """autogenerated by genpy from orrosplanning/IKResponse.msg. Do not edit."""
00489 import sys
00490 python3 = True if sys.hexversion > 0x03000000 else False
00491 import genpy
00492 import struct
00493 
00494 import trajectory_msgs.msg
00495 import arm_navigation_msgs.msg
00496 import genpy
00497 import std_msgs.msg
00498 
00499 class IKResponse(genpy.Message):
00500   _md5sum = "5f574f395e24640186b5db7e64e4180d"
00501   _type = "orrosplanning/IKResponse"
00502   _has_header = False #flag to mark the presence of a Header object
00503   _full_text = """
00504 trajectory_msgs/JointTrajectory solutions
00505 arm_navigation_msgs/ArmNavigationErrorCodes error_code
00506 
00507 
00508 ================================================================================
00509 MSG: trajectory_msgs/JointTrajectory
00510 Header header
00511 string[] joint_names
00512 JointTrajectoryPoint[] points
00513 ================================================================================
00514 MSG: std_msgs/Header
00515 # Standard metadata for higher-level stamped data types.
00516 # This is generally used to communicate timestamped data 
00517 # in a particular coordinate frame.
00518 # 
00519 # sequence ID: consecutively increasing ID 
00520 uint32 seq
00521 #Two-integer timestamp that is expressed as:
00522 # * stamp.secs: seconds (stamp_secs) since epoch
00523 # * stamp.nsecs: nanoseconds since stamp_secs
00524 # time-handling sugar is provided by the client library
00525 time stamp
00526 #Frame this data is associated with
00527 # 0: no frame
00528 # 1: global frame
00529 string frame_id
00530 
00531 ================================================================================
00532 MSG: trajectory_msgs/JointTrajectoryPoint
00533 float64[] positions
00534 float64[] velocities
00535 float64[] accelerations
00536 duration time_from_start
00537 ================================================================================
00538 MSG: arm_navigation_msgs/ArmNavigationErrorCodes
00539 int32 val
00540 
00541 # overall behavior
00542 int32 PLANNING_FAILED=-1
00543 int32 SUCCESS=1
00544 int32 TIMED_OUT=-2
00545 
00546 # start state errors
00547 int32 START_STATE_IN_COLLISION=-3
00548 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
00549 
00550 # goal errors
00551 int32 GOAL_IN_COLLISION=-5
00552 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
00553 
00554 # robot state
00555 int32 INVALID_ROBOT_STATE=-7
00556 int32 INCOMPLETE_ROBOT_STATE=-8
00557 
00558 # planning request errors
00559 int32 INVALID_PLANNER_ID=-9
00560 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
00561 int32 INVALID_ALLOWED_PLANNING_TIME=-11
00562 int32 INVALID_GROUP_NAME=-12
00563 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
00564 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
00565 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
00566 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
00567 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
00568 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
00569 
00570 # state/trajectory monitor errors
00571 int32 INVALID_TRAJECTORY=-19
00572 int32 INVALID_INDEX=-20
00573 int32 JOINT_LIMITS_VIOLATED=-21
00574 int32 PATH_CONSTRAINTS_VIOLATED=-22
00575 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
00576 int32 GOAL_CONSTRAINTS_VIOLATED=-24
00577 int32 JOINTS_NOT_MOVING=-25
00578 int32 TRAJECTORY_CONTROLLER_FAILED=-26
00579 
00580 # system errors
00581 int32 FRAME_TRANSFORM_FAILURE=-27
00582 int32 COLLISION_CHECKING_UNAVAILABLE=-28
00583 int32 ROBOT_STATE_STALE=-29
00584 int32 SENSOR_INFO_STALE=-30
00585 
00586 # kinematics errors
00587 int32 NO_IK_SOLUTION=-31
00588 int32 INVALID_LINK_NAME=-32
00589 int32 IK_LINK_IN_COLLISION=-33
00590 int32 NO_FK_SOLUTION=-34
00591 int32 KINEMATICS_STATE_IN_COLLISION=-35
00592 
00593 # general errors
00594 int32 INVALID_TIMEOUT=-36
00595 
00596 
00597 """
00598   __slots__ = ['solutions','error_code']
00599   _slot_types = ['trajectory_msgs/JointTrajectory','arm_navigation_msgs/ArmNavigationErrorCodes']
00600 
00601   def __init__(self, *args, **kwds):
00602     """
00603     Constructor. Any message fields that are implicitly/explicitly
00604     set to None will be assigned a default value. The recommend
00605     use is keyword arguments as this is more robust to future message
00606     changes.  You cannot mix in-order arguments and keyword arguments.
00607 
00608     The available fields are:
00609        solutions,error_code
00610 
00611     :param args: complete set of field values, in .msg order
00612     :param kwds: use keyword arguments corresponding to message field names
00613     to set specific fields.
00614     """
00615     if args or kwds:
00616       super(IKResponse, self).__init__(*args, **kwds)
00617       #message fields cannot be None, assign default values for those that are
00618       if self.solutions is None:
00619         self.solutions = trajectory_msgs.msg.JointTrajectory()
00620       if self.error_code is None:
00621         self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00622     else:
00623       self.solutions = trajectory_msgs.msg.JointTrajectory()
00624       self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00625 
00626   def _get_types(self):
00627     """
00628     internal API method
00629     """
00630     return self._slot_types
00631 
00632   def serialize(self, buff):
00633     """
00634     serialize message into buffer
00635     :param buff: buffer, ``StringIO``
00636     """
00637     try:
00638       _x = self
00639       buff.write(_struct_3I.pack(_x.solutions.header.seq, _x.solutions.header.stamp.secs, _x.solutions.header.stamp.nsecs))
00640       _x = self.solutions.header.frame_id
00641       length = len(_x)
00642       if python3 or type(_x) == unicode:
00643         _x = _x.encode('utf-8')
00644         length = len(_x)
00645       buff.write(struct.pack('<I%ss'%length, length, _x))
00646       length = len(self.solutions.joint_names)
00647       buff.write(_struct_I.pack(length))
00648       for val1 in self.solutions.joint_names:
00649         length = len(val1)
00650         if python3 or type(val1) == unicode:
00651           val1 = val1.encode('utf-8')
00652           length = len(val1)
00653         buff.write(struct.pack('<I%ss'%length, length, val1))
00654       length = len(self.solutions.points)
00655       buff.write(_struct_I.pack(length))
00656       for val1 in self.solutions.points:
00657         length = len(val1.positions)
00658         buff.write(_struct_I.pack(length))
00659         pattern = '<%sd'%length
00660         buff.write(struct.pack(pattern, *val1.positions))
00661         length = len(val1.velocities)
00662         buff.write(_struct_I.pack(length))
00663         pattern = '<%sd'%length
00664         buff.write(struct.pack(pattern, *val1.velocities))
00665         length = len(val1.accelerations)
00666         buff.write(_struct_I.pack(length))
00667         pattern = '<%sd'%length
00668         buff.write(struct.pack(pattern, *val1.accelerations))
00669         _v1 = val1.time_from_start
00670         _x = _v1
00671         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00672       buff.write(_struct_i.pack(self.error_code.val))
00673     except struct.error as se: self._check_types(se)
00674     except TypeError as te: self._check_types(te)
00675 
00676   def deserialize(self, str):
00677     """
00678     unpack serialized message in str into this message instance
00679     :param str: byte array of serialized message, ``str``
00680     """
00681     try:
00682       if self.solutions is None:
00683         self.solutions = trajectory_msgs.msg.JointTrajectory()
00684       if self.error_code is None:
00685         self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00686       end = 0
00687       _x = self
00688       start = end
00689       end += 12
00690       (_x.solutions.header.seq, _x.solutions.header.stamp.secs, _x.solutions.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00691       start = end
00692       end += 4
00693       (length,) = _struct_I.unpack(str[start:end])
00694       start = end
00695       end += length
00696       if python3:
00697         self.solutions.header.frame_id = str[start:end].decode('utf-8')
00698       else:
00699         self.solutions.header.frame_id = str[start:end]
00700       start = end
00701       end += 4
00702       (length,) = _struct_I.unpack(str[start:end])
00703       self.solutions.joint_names = []
00704       for i in range(0, length):
00705         start = end
00706         end += 4
00707         (length,) = _struct_I.unpack(str[start:end])
00708         start = end
00709         end += length
00710         if python3:
00711           val1 = str[start:end].decode('utf-8')
00712         else:
00713           val1 = str[start:end]
00714         self.solutions.joint_names.append(val1)
00715       start = end
00716       end += 4
00717       (length,) = _struct_I.unpack(str[start:end])
00718       self.solutions.points = []
00719       for i in range(0, length):
00720         val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00721         start = end
00722         end += 4
00723         (length,) = _struct_I.unpack(str[start:end])
00724         pattern = '<%sd'%length
00725         start = end
00726         end += struct.calcsize(pattern)
00727         val1.positions = struct.unpack(pattern, str[start:end])
00728         start = end
00729         end += 4
00730         (length,) = _struct_I.unpack(str[start:end])
00731         pattern = '<%sd'%length
00732         start = end
00733         end += struct.calcsize(pattern)
00734         val1.velocities = struct.unpack(pattern, str[start:end])
00735         start = end
00736         end += 4
00737         (length,) = _struct_I.unpack(str[start:end])
00738         pattern = '<%sd'%length
00739         start = end
00740         end += struct.calcsize(pattern)
00741         val1.accelerations = struct.unpack(pattern, str[start:end])
00742         _v2 = val1.time_from_start
00743         _x = _v2
00744         start = end
00745         end += 8
00746         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00747         self.solutions.points.append(val1)
00748       start = end
00749       end += 4
00750       (self.error_code.val,) = _struct_i.unpack(str[start:end])
00751       return self
00752     except struct.error as e:
00753       raise genpy.DeserializationError(e) #most likely buffer underfill
00754 
00755 
00756   def serialize_numpy(self, buff, numpy):
00757     """
00758     serialize message with numpy array types into buffer
00759     :param buff: buffer, ``StringIO``
00760     :param numpy: numpy python module
00761     """
00762     try:
00763       _x = self
00764       buff.write(_struct_3I.pack(_x.solutions.header.seq, _x.solutions.header.stamp.secs, _x.solutions.header.stamp.nsecs))
00765       _x = self.solutions.header.frame_id
00766       length = len(_x)
00767       if python3 or type(_x) == unicode:
00768         _x = _x.encode('utf-8')
00769         length = len(_x)
00770       buff.write(struct.pack('<I%ss'%length, length, _x))
00771       length = len(self.solutions.joint_names)
00772       buff.write(_struct_I.pack(length))
00773       for val1 in self.solutions.joint_names:
00774         length = len(val1)
00775         if python3 or type(val1) == unicode:
00776           val1 = val1.encode('utf-8')
00777           length = len(val1)
00778         buff.write(struct.pack('<I%ss'%length, length, val1))
00779       length = len(self.solutions.points)
00780       buff.write(_struct_I.pack(length))
00781       for val1 in self.solutions.points:
00782         length = len(val1.positions)
00783         buff.write(_struct_I.pack(length))
00784         pattern = '<%sd'%length
00785         buff.write(val1.positions.tostring())
00786         length = len(val1.velocities)
00787         buff.write(_struct_I.pack(length))
00788         pattern = '<%sd'%length
00789         buff.write(val1.velocities.tostring())
00790         length = len(val1.accelerations)
00791         buff.write(_struct_I.pack(length))
00792         pattern = '<%sd'%length
00793         buff.write(val1.accelerations.tostring())
00794         _v3 = val1.time_from_start
00795         _x = _v3
00796         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00797       buff.write(_struct_i.pack(self.error_code.val))
00798     except struct.error as se: self._check_types(se)
00799     except TypeError as te: self._check_types(te)
00800 
00801   def deserialize_numpy(self, str, numpy):
00802     """
00803     unpack serialized message in str into this message instance using numpy for array types
00804     :param str: byte array of serialized message, ``str``
00805     :param numpy: numpy python module
00806     """
00807     try:
00808       if self.solutions is None:
00809         self.solutions = trajectory_msgs.msg.JointTrajectory()
00810       if self.error_code is None:
00811         self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00812       end = 0
00813       _x = self
00814       start = end
00815       end += 12
00816       (_x.solutions.header.seq, _x.solutions.header.stamp.secs, _x.solutions.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00817       start = end
00818       end += 4
00819       (length,) = _struct_I.unpack(str[start:end])
00820       start = end
00821       end += length
00822       if python3:
00823         self.solutions.header.frame_id = str[start:end].decode('utf-8')
00824       else:
00825         self.solutions.header.frame_id = str[start:end]
00826       start = end
00827       end += 4
00828       (length,) = _struct_I.unpack(str[start:end])
00829       self.solutions.joint_names = []
00830       for i in range(0, length):
00831         start = end
00832         end += 4
00833         (length,) = _struct_I.unpack(str[start:end])
00834         start = end
00835         end += length
00836         if python3:
00837           val1 = str[start:end].decode('utf-8')
00838         else:
00839           val1 = str[start:end]
00840         self.solutions.joint_names.append(val1)
00841       start = end
00842       end += 4
00843       (length,) = _struct_I.unpack(str[start:end])
00844       self.solutions.points = []
00845       for i in range(0, length):
00846         val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00847         start = end
00848         end += 4
00849         (length,) = _struct_I.unpack(str[start:end])
00850         pattern = '<%sd'%length
00851         start = end
00852         end += struct.calcsize(pattern)
00853         val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00854         start = end
00855         end += 4
00856         (length,) = _struct_I.unpack(str[start:end])
00857         pattern = '<%sd'%length
00858         start = end
00859         end += struct.calcsize(pattern)
00860         val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00861         start = end
00862         end += 4
00863         (length,) = _struct_I.unpack(str[start:end])
00864         pattern = '<%sd'%length
00865         start = end
00866         end += struct.calcsize(pattern)
00867         val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00868         _v4 = val1.time_from_start
00869         _x = _v4
00870         start = end
00871         end += 8
00872         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00873         self.solutions.points.append(val1)
00874       start = end
00875       end += 4
00876       (self.error_code.val,) = _struct_i.unpack(str[start:end])
00877       return self
00878     except struct.error as e:
00879       raise genpy.DeserializationError(e) #most likely buffer underfill
00880 
00881 _struct_I = genpy.struct_I
00882 _struct_i = struct.Struct("<i")
00883 _struct_3I = struct.Struct("<3I")
00884 _struct_2i = struct.Struct("<2i")
00885 class IK(object):
00886   _type          = 'orrosplanning/IK'
00887   _md5sum = '31cc39758dd73da8b3d6340b2388f6a8'
00888   _request_class  = IKRequest
00889   _response_class = IKResponse
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


orrosplanning
Author(s): Rosen Diankov (rosen.diankov@gmail.com)
autogenerated on Sat Mar 23 2013 22:32:56