00001 """autogenerated by genmsg_py from Grasp.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import std_msgs.msg
00007 import sensor_msgs.msg
00008
00009 class Grasp(roslib.message.Message):
00010 _md5sum = "a447abc9a49aaff833c07915ee5565b4"
00011 _type = "object_manipulation_msgs/Grasp"
00012 _has_header = False
00013 _full_text = """
00014 # The internal posture of the hand for the pre-grasp
00015 # only positions are used
00016 sensor_msgs/JointState pre_grasp_posture
00017
00018 # The internal posture of the hand for the grasp
00019 # positions and efforts are used
00020 sensor_msgs/JointState grasp_posture
00021
00022 # The position of the end-effector for the grasp relative to the object
00023 geometry_msgs/Pose grasp_pose
00024
00025 # The estimated probability of success for this grasp
00026 float64 success_probability
00027
00028 # Debug flag to indicate that this grasp would be the best in its cluster
00029 bool cluster_rep
00030 ================================================================================
00031 MSG: sensor_msgs/JointState
00032 # This is a message that holds data to describe the state of a set of torque controlled joints.
00033 #
00034 # The state of each joint (revolute or prismatic) is defined by:
00035 # * the position of the joint (rad or m),
00036 # * the velocity of the joint (rad/s or m/s) and
00037 # * the effort that is applied in the joint (Nm or N).
00038 #
00039 # Each joint is uniquely identified by its name
00040 # The header specifies the time at which the joint states were recorded. All the joint states
00041 # in one message have to be recorded at the same time.
00042 #
00043 # This message consists of a multiple arrays, one for each part of the joint state.
00044 # The goal is to make each of the fields optional. When e.g. your joints have no
00045 # effort associated with them, you can leave the effort array empty.
00046 #
00047 # All arrays in this message should have the same size, or be empty.
00048 # This is the only way to uniquely associate the joint name with the correct
00049 # states.
00050
00051
00052 Header header
00053
00054 string[] name
00055 float64[] position
00056 float64[] velocity
00057 float64[] effort
00058
00059 ================================================================================
00060 MSG: std_msgs/Header
00061 # Standard metadata for higher-level stamped data types.
00062 # This is generally used to communicate timestamped data
00063 # in a particular coordinate frame.
00064 #
00065 # sequence ID: consecutively increasing ID
00066 uint32 seq
00067 #Two-integer timestamp that is expressed as:
00068 # * stamp.secs: seconds (stamp_secs) since epoch
00069 # * stamp.nsecs: nanoseconds since stamp_secs
00070 # time-handling sugar is provided by the client library
00071 time stamp
00072 #Frame this data is associated with
00073 # 0: no frame
00074 # 1: global frame
00075 string frame_id
00076
00077 ================================================================================
00078 MSG: geometry_msgs/Pose
00079 # A representation of pose in free space, composed of postion and orientation.
00080 Point position
00081 Quaternion orientation
00082
00083 ================================================================================
00084 MSG: geometry_msgs/Point
00085 # This contains the position of a point in free space
00086 float64 x
00087 float64 y
00088 float64 z
00089
00090 ================================================================================
00091 MSG: geometry_msgs/Quaternion
00092 # This represents an orientation in free space in quaternion form.
00093
00094 float64 x
00095 float64 y
00096 float64 z
00097 float64 w
00098
00099 """
00100 __slots__ = ['pre_grasp_posture','grasp_posture','grasp_pose','success_probability','cluster_rep']
00101 _slot_types = ['sensor_msgs/JointState','sensor_msgs/JointState','geometry_msgs/Pose','float64','bool']
00102
00103 def __init__(self, *args, **kwds):
00104 """
00105 Constructor. Any message fields that are implicitly/explicitly
00106 set to None will be assigned a default value. The recommend
00107 use is keyword arguments as this is more robust to future message
00108 changes. You cannot mix in-order arguments and keyword arguments.
00109
00110 The available fields are:
00111 pre_grasp_posture,grasp_posture,grasp_pose,success_probability,cluster_rep
00112
00113 @param args: complete set of field values, in .msg order
00114 @param kwds: use keyword arguments corresponding to message field names
00115 to set specific fields.
00116 """
00117 if args or kwds:
00118 super(Grasp, self).__init__(*args, **kwds)
00119
00120 if self.pre_grasp_posture is None:
00121 self.pre_grasp_posture = sensor_msgs.msg.JointState()
00122 if self.grasp_posture is None:
00123 self.grasp_posture = sensor_msgs.msg.JointState()
00124 if self.grasp_pose is None:
00125 self.grasp_pose = geometry_msgs.msg.Pose()
00126 if self.success_probability is None:
00127 self.success_probability = 0.
00128 if self.cluster_rep is None:
00129 self.cluster_rep = False
00130 else:
00131 self.pre_grasp_posture = sensor_msgs.msg.JointState()
00132 self.grasp_posture = sensor_msgs.msg.JointState()
00133 self.grasp_pose = geometry_msgs.msg.Pose()
00134 self.success_probability = 0.
00135 self.cluster_rep = False
00136
00137 def _get_types(self):
00138 """
00139 internal API method
00140 """
00141 return self._slot_types
00142
00143 def serialize(self, buff):
00144 """
00145 serialize message into buffer
00146 @param buff: buffer
00147 @type buff: StringIO
00148 """
00149 try:
00150 _x = self
00151 buff.write(_struct_3I.pack(_x.pre_grasp_posture.header.seq, _x.pre_grasp_posture.header.stamp.secs, _x.pre_grasp_posture.header.stamp.nsecs))
00152 _x = self.pre_grasp_posture.header.frame_id
00153 length = len(_x)
00154 buff.write(struct.pack('<I%ss'%length, length, _x))
00155 length = len(self.pre_grasp_posture.name)
00156 buff.write(_struct_I.pack(length))
00157 for val1 in self.pre_grasp_posture.name:
00158 length = len(val1)
00159 buff.write(struct.pack('<I%ss'%length, length, val1))
00160 length = len(self.pre_grasp_posture.position)
00161 buff.write(_struct_I.pack(length))
00162 pattern = '<%sd'%length
00163 buff.write(struct.pack(pattern, *self.pre_grasp_posture.position))
00164 length = len(self.pre_grasp_posture.velocity)
00165 buff.write(_struct_I.pack(length))
00166 pattern = '<%sd'%length
00167 buff.write(struct.pack(pattern, *self.pre_grasp_posture.velocity))
00168 length = len(self.pre_grasp_posture.effort)
00169 buff.write(_struct_I.pack(length))
00170 pattern = '<%sd'%length
00171 buff.write(struct.pack(pattern, *self.pre_grasp_posture.effort))
00172 _x = self
00173 buff.write(_struct_3I.pack(_x.grasp_posture.header.seq, _x.grasp_posture.header.stamp.secs, _x.grasp_posture.header.stamp.nsecs))
00174 _x = self.grasp_posture.header.frame_id
00175 length = len(_x)
00176 buff.write(struct.pack('<I%ss'%length, length, _x))
00177 length = len(self.grasp_posture.name)
00178 buff.write(_struct_I.pack(length))
00179 for val1 in self.grasp_posture.name:
00180 length = len(val1)
00181 buff.write(struct.pack('<I%ss'%length, length, val1))
00182 length = len(self.grasp_posture.position)
00183 buff.write(_struct_I.pack(length))
00184 pattern = '<%sd'%length
00185 buff.write(struct.pack(pattern, *self.grasp_posture.position))
00186 length = len(self.grasp_posture.velocity)
00187 buff.write(_struct_I.pack(length))
00188 pattern = '<%sd'%length
00189 buff.write(struct.pack(pattern, *self.grasp_posture.velocity))
00190 length = len(self.grasp_posture.effort)
00191 buff.write(_struct_I.pack(length))
00192 pattern = '<%sd'%length
00193 buff.write(struct.pack(pattern, *self.grasp_posture.effort))
00194 _x = self
00195 buff.write(_struct_8dB.pack(_x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.success_probability, _x.cluster_rep))
00196 except struct.error, se: self._check_types(se)
00197 except TypeError, te: self._check_types(te)
00198
00199 def deserialize(self, str):
00200 """
00201 unpack serialized message in str into this message instance
00202 @param str: byte array of serialized message
00203 @type str: str
00204 """
00205 try:
00206 if self.pre_grasp_posture is None:
00207 self.pre_grasp_posture = sensor_msgs.msg.JointState()
00208 if self.grasp_posture is None:
00209 self.grasp_posture = sensor_msgs.msg.JointState()
00210 if self.grasp_pose is None:
00211 self.grasp_pose = geometry_msgs.msg.Pose()
00212 end = 0
00213 _x = self
00214 start = end
00215 end += 12
00216 (_x.pre_grasp_posture.header.seq, _x.pre_grasp_posture.header.stamp.secs, _x.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00217 start = end
00218 end += 4
00219 (length,) = _struct_I.unpack(str[start:end])
00220 start = end
00221 end += length
00222 self.pre_grasp_posture.header.frame_id = str[start:end]
00223 start = end
00224 end += 4
00225 (length,) = _struct_I.unpack(str[start:end])
00226 self.pre_grasp_posture.name = []
00227 for i in xrange(0, length):
00228 start = end
00229 end += 4
00230 (length,) = _struct_I.unpack(str[start:end])
00231 start = end
00232 end += length
00233 val1 = str[start:end]
00234 self.pre_grasp_posture.name.append(val1)
00235 start = end
00236 end += 4
00237 (length,) = _struct_I.unpack(str[start:end])
00238 pattern = '<%sd'%length
00239 start = end
00240 end += struct.calcsize(pattern)
00241 self.pre_grasp_posture.position = struct.unpack(pattern, str[start:end])
00242 start = end
00243 end += 4
00244 (length,) = _struct_I.unpack(str[start:end])
00245 pattern = '<%sd'%length
00246 start = end
00247 end += struct.calcsize(pattern)
00248 self.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00249 start = end
00250 end += 4
00251 (length,) = _struct_I.unpack(str[start:end])
00252 pattern = '<%sd'%length
00253 start = end
00254 end += struct.calcsize(pattern)
00255 self.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end])
00256 _x = self
00257 start = end
00258 end += 12
00259 (_x.grasp_posture.header.seq, _x.grasp_posture.header.stamp.secs, _x.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00260 start = end
00261 end += 4
00262 (length,) = _struct_I.unpack(str[start:end])
00263 start = end
00264 end += length
00265 self.grasp_posture.header.frame_id = str[start:end]
00266 start = end
00267 end += 4
00268 (length,) = _struct_I.unpack(str[start:end])
00269 self.grasp_posture.name = []
00270 for i in xrange(0, length):
00271 start = end
00272 end += 4
00273 (length,) = _struct_I.unpack(str[start:end])
00274 start = end
00275 end += length
00276 val1 = str[start:end]
00277 self.grasp_posture.name.append(val1)
00278 start = end
00279 end += 4
00280 (length,) = _struct_I.unpack(str[start:end])
00281 pattern = '<%sd'%length
00282 start = end
00283 end += struct.calcsize(pattern)
00284 self.grasp_posture.position = struct.unpack(pattern, str[start:end])
00285 start = end
00286 end += 4
00287 (length,) = _struct_I.unpack(str[start:end])
00288 pattern = '<%sd'%length
00289 start = end
00290 end += struct.calcsize(pattern)
00291 self.grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00292 start = end
00293 end += 4
00294 (length,) = _struct_I.unpack(str[start:end])
00295 pattern = '<%sd'%length
00296 start = end
00297 end += struct.calcsize(pattern)
00298 self.grasp_posture.effort = struct.unpack(pattern, str[start:end])
00299 _x = self
00300 start = end
00301 end += 65
00302 (_x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.success_probability, _x.cluster_rep,) = _struct_8dB.unpack(str[start:end])
00303 self.cluster_rep = bool(self.cluster_rep)
00304 return self
00305 except struct.error, e:
00306 raise roslib.message.DeserializationError(e)
00307
00308
00309 def serialize_numpy(self, buff, numpy):
00310 """
00311 serialize message with numpy array types into buffer
00312 @param buff: buffer
00313 @type buff: StringIO
00314 @param numpy: numpy python module
00315 @type numpy module
00316 """
00317 try:
00318 _x = self
00319 buff.write(_struct_3I.pack(_x.pre_grasp_posture.header.seq, _x.pre_grasp_posture.header.stamp.secs, _x.pre_grasp_posture.header.stamp.nsecs))
00320 _x = self.pre_grasp_posture.header.frame_id
00321 length = len(_x)
00322 buff.write(struct.pack('<I%ss'%length, length, _x))
00323 length = len(self.pre_grasp_posture.name)
00324 buff.write(_struct_I.pack(length))
00325 for val1 in self.pre_grasp_posture.name:
00326 length = len(val1)
00327 buff.write(struct.pack('<I%ss'%length, length, val1))
00328 length = len(self.pre_grasp_posture.position)
00329 buff.write(_struct_I.pack(length))
00330 pattern = '<%sd'%length
00331 buff.write(self.pre_grasp_posture.position.tostring())
00332 length = len(self.pre_grasp_posture.velocity)
00333 buff.write(_struct_I.pack(length))
00334 pattern = '<%sd'%length
00335 buff.write(self.pre_grasp_posture.velocity.tostring())
00336 length = len(self.pre_grasp_posture.effort)
00337 buff.write(_struct_I.pack(length))
00338 pattern = '<%sd'%length
00339 buff.write(self.pre_grasp_posture.effort.tostring())
00340 _x = self
00341 buff.write(_struct_3I.pack(_x.grasp_posture.header.seq, _x.grasp_posture.header.stamp.secs, _x.grasp_posture.header.stamp.nsecs))
00342 _x = self.grasp_posture.header.frame_id
00343 length = len(_x)
00344 buff.write(struct.pack('<I%ss'%length, length, _x))
00345 length = len(self.grasp_posture.name)
00346 buff.write(_struct_I.pack(length))
00347 for val1 in self.grasp_posture.name:
00348 length = len(val1)
00349 buff.write(struct.pack('<I%ss'%length, length, val1))
00350 length = len(self.grasp_posture.position)
00351 buff.write(_struct_I.pack(length))
00352 pattern = '<%sd'%length
00353 buff.write(self.grasp_posture.position.tostring())
00354 length = len(self.grasp_posture.velocity)
00355 buff.write(_struct_I.pack(length))
00356 pattern = '<%sd'%length
00357 buff.write(self.grasp_posture.velocity.tostring())
00358 length = len(self.grasp_posture.effort)
00359 buff.write(_struct_I.pack(length))
00360 pattern = '<%sd'%length
00361 buff.write(self.grasp_posture.effort.tostring())
00362 _x = self
00363 buff.write(_struct_8dB.pack(_x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.success_probability, _x.cluster_rep))
00364 except struct.error, se: self._check_types(se)
00365 except TypeError, te: self._check_types(te)
00366
00367 def deserialize_numpy(self, str, numpy):
00368 """
00369 unpack serialized message in str into this message instance using numpy for array types
00370 @param str: byte array of serialized message
00371 @type str: str
00372 @param numpy: numpy python module
00373 @type numpy: module
00374 """
00375 try:
00376 if self.pre_grasp_posture is None:
00377 self.pre_grasp_posture = sensor_msgs.msg.JointState()
00378 if self.grasp_posture is None:
00379 self.grasp_posture = sensor_msgs.msg.JointState()
00380 if self.grasp_pose is None:
00381 self.grasp_pose = geometry_msgs.msg.Pose()
00382 end = 0
00383 _x = self
00384 start = end
00385 end += 12
00386 (_x.pre_grasp_posture.header.seq, _x.pre_grasp_posture.header.stamp.secs, _x.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00387 start = end
00388 end += 4
00389 (length,) = _struct_I.unpack(str[start:end])
00390 start = end
00391 end += length
00392 self.pre_grasp_posture.header.frame_id = str[start:end]
00393 start = end
00394 end += 4
00395 (length,) = _struct_I.unpack(str[start:end])
00396 self.pre_grasp_posture.name = []
00397 for i in xrange(0, length):
00398 start = end
00399 end += 4
00400 (length,) = _struct_I.unpack(str[start:end])
00401 start = end
00402 end += length
00403 val1 = str[start:end]
00404 self.pre_grasp_posture.name.append(val1)
00405 start = end
00406 end += 4
00407 (length,) = _struct_I.unpack(str[start:end])
00408 pattern = '<%sd'%length
00409 start = end
00410 end += struct.calcsize(pattern)
00411 self.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00412 start = end
00413 end += 4
00414 (length,) = _struct_I.unpack(str[start:end])
00415 pattern = '<%sd'%length
00416 start = end
00417 end += struct.calcsize(pattern)
00418 self.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00419 start = end
00420 end += 4
00421 (length,) = _struct_I.unpack(str[start:end])
00422 pattern = '<%sd'%length
00423 start = end
00424 end += struct.calcsize(pattern)
00425 self.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00426 _x = self
00427 start = end
00428 end += 12
00429 (_x.grasp_posture.header.seq, _x.grasp_posture.header.stamp.secs, _x.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00430 start = end
00431 end += 4
00432 (length,) = _struct_I.unpack(str[start:end])
00433 start = end
00434 end += length
00435 self.grasp_posture.header.frame_id = str[start:end]
00436 start = end
00437 end += 4
00438 (length,) = _struct_I.unpack(str[start:end])
00439 self.grasp_posture.name = []
00440 for i in xrange(0, length):
00441 start = end
00442 end += 4
00443 (length,) = _struct_I.unpack(str[start:end])
00444 start = end
00445 end += length
00446 val1 = str[start:end]
00447 self.grasp_posture.name.append(val1)
00448 start = end
00449 end += 4
00450 (length,) = _struct_I.unpack(str[start:end])
00451 pattern = '<%sd'%length
00452 start = end
00453 end += struct.calcsize(pattern)
00454 self.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00455 start = end
00456 end += 4
00457 (length,) = _struct_I.unpack(str[start:end])
00458 pattern = '<%sd'%length
00459 start = end
00460 end += struct.calcsize(pattern)
00461 self.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00462 start = end
00463 end += 4
00464 (length,) = _struct_I.unpack(str[start:end])
00465 pattern = '<%sd'%length
00466 start = end
00467 end += struct.calcsize(pattern)
00468 self.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00469 _x = self
00470 start = end
00471 end += 65
00472 (_x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.success_probability, _x.cluster_rep,) = _struct_8dB.unpack(str[start:end])
00473 self.cluster_rep = bool(self.cluster_rep)
00474 return self
00475 except struct.error, e:
00476 raise roslib.message.DeserializationError(e)
00477
00478 _struct_I = roslib.message.struct_I
00479 _struct_3I = struct.Struct("<3I")
00480 _struct_8dB = struct.Struct("<8dB")