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


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 02:58:11