00001 """autogenerated by genpy from pr2_grasp_adjust/GraspAdjustRequest.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
00010 class GraspAdjustRequest(genpy.Message):
00011 _md5sum = "e7ccb113bffaf7f7554b005b509b114a"
00012 _type = "pr2_grasp_adjust/GraspAdjustRequest"
00013 _has_header = False
00014 _full_text = """geometry_msgs/PoseStamped grasp_pose
00015 geometry_msgs/Vector3 roi_dims
00016 uint8 search_mode
00017
00018 int32 GLOBAL_SEARCH = 0
00019 int32 LOCAL_SEARCH = 1
00020 int32 SINGLE_POSE = 2
00021
00022
00023 ================================================================================
00024 MSG: geometry_msgs/PoseStamped
00025 # A Pose with reference coordinate frame and timestamp
00026 Header header
00027 Pose pose
00028
00029 ================================================================================
00030 MSG: std_msgs/Header
00031 # Standard metadata for higher-level stamped data types.
00032 # This is generally used to communicate timestamped data
00033 # in a particular coordinate frame.
00034 #
00035 # sequence ID: consecutively increasing ID
00036 uint32 seq
00037 #Two-integer timestamp that is expressed as:
00038 # * stamp.secs: seconds (stamp_secs) since epoch
00039 # * stamp.nsecs: nanoseconds since stamp_secs
00040 # time-handling sugar is provided by the client library
00041 time stamp
00042 #Frame this data is associated with
00043 # 0: no frame
00044 # 1: global frame
00045 string frame_id
00046
00047 ================================================================================
00048 MSG: geometry_msgs/Pose
00049 # A representation of pose in free space, composed of postion and orientation.
00050 Point position
00051 Quaternion orientation
00052
00053 ================================================================================
00054 MSG: geometry_msgs/Point
00055 # This contains the position of a point in free space
00056 float64 x
00057 float64 y
00058 float64 z
00059
00060 ================================================================================
00061 MSG: geometry_msgs/Quaternion
00062 # This represents an orientation in free space in quaternion form.
00063
00064 float64 x
00065 float64 y
00066 float64 z
00067 float64 w
00068
00069 ================================================================================
00070 MSG: geometry_msgs/Vector3
00071 # This represents a vector in free space.
00072
00073 float64 x
00074 float64 y
00075 float64 z
00076 """
00077
00078 GLOBAL_SEARCH = 0
00079 LOCAL_SEARCH = 1
00080 SINGLE_POSE = 2
00081
00082 __slots__ = ['grasp_pose','roi_dims','search_mode']
00083 _slot_types = ['geometry_msgs/PoseStamped','geometry_msgs/Vector3','uint8']
00084
00085 def __init__(self, *args, **kwds):
00086 """
00087 Constructor. Any message fields that are implicitly/explicitly
00088 set to None will be assigned a default value. The recommend
00089 use is keyword arguments as this is more robust to future message
00090 changes. You cannot mix in-order arguments and keyword arguments.
00091
00092 The available fields are:
00093 grasp_pose,roi_dims,search_mode
00094
00095 :param args: complete set of field values, in .msg order
00096 :param kwds: use keyword arguments corresponding to message field names
00097 to set specific fields.
00098 """
00099 if args or kwds:
00100 super(GraspAdjustRequest, self).__init__(*args, **kwds)
00101
00102 if self.grasp_pose is None:
00103 self.grasp_pose = geometry_msgs.msg.PoseStamped()
00104 if self.roi_dims is None:
00105 self.roi_dims = geometry_msgs.msg.Vector3()
00106 if self.search_mode is None:
00107 self.search_mode = 0
00108 else:
00109 self.grasp_pose = geometry_msgs.msg.PoseStamped()
00110 self.roi_dims = geometry_msgs.msg.Vector3()
00111 self.search_mode = 0
00112
00113 def _get_types(self):
00114 """
00115 internal API method
00116 """
00117 return self._slot_types
00118
00119 def serialize(self, buff):
00120 """
00121 serialize message into buffer
00122 :param buff: buffer, ``StringIO``
00123 """
00124 try:
00125 _x = self
00126 buff.write(_struct_3I.pack(_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs))
00127 _x = self.grasp_pose.header.frame_id
00128 length = len(_x)
00129 if python3 or type(_x) == unicode:
00130 _x = _x.encode('utf-8')
00131 length = len(_x)
00132 buff.write(struct.pack('<I%ss'%length, length, _x))
00133 _x = self
00134 buff.write(_struct_10dB.pack(_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode))
00135 except struct.error as se: self._check_types(se)
00136 except TypeError as te: self._check_types(te)
00137
00138 def deserialize(self, str):
00139 """
00140 unpack serialized message in str into this message instance
00141 :param str: byte array of serialized message, ``str``
00142 """
00143 try:
00144 if self.grasp_pose is None:
00145 self.grasp_pose = geometry_msgs.msg.PoseStamped()
00146 if self.roi_dims is None:
00147 self.roi_dims = geometry_msgs.msg.Vector3()
00148 end = 0
00149 _x = self
00150 start = end
00151 end += 12
00152 (_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00153 start = end
00154 end += 4
00155 (length,) = _struct_I.unpack(str[start:end])
00156 start = end
00157 end += length
00158 if python3:
00159 self.grasp_pose.header.frame_id = str[start:end].decode('utf-8')
00160 else:
00161 self.grasp_pose.header.frame_id = str[start:end]
00162 _x = self
00163 start = end
00164 end += 81
00165 (_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode,) = _struct_10dB.unpack(str[start:end])
00166 return self
00167 except struct.error as e:
00168 raise genpy.DeserializationError(e)
00169
00170
00171 def serialize_numpy(self, buff, numpy):
00172 """
00173 serialize message with numpy array types into buffer
00174 :param buff: buffer, ``StringIO``
00175 :param numpy: numpy python module
00176 """
00177 try:
00178 _x = self
00179 buff.write(_struct_3I.pack(_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs))
00180 _x = self.grasp_pose.header.frame_id
00181 length = len(_x)
00182 if python3 or type(_x) == unicode:
00183 _x = _x.encode('utf-8')
00184 length = len(_x)
00185 buff.write(struct.pack('<I%ss'%length, length, _x))
00186 _x = self
00187 buff.write(_struct_10dB.pack(_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode))
00188 except struct.error as se: self._check_types(se)
00189 except TypeError as te: self._check_types(te)
00190
00191 def deserialize_numpy(self, str, numpy):
00192 """
00193 unpack serialized message in str into this message instance using numpy for array types
00194 :param str: byte array of serialized message, ``str``
00195 :param numpy: numpy python module
00196 """
00197 try:
00198 if self.grasp_pose is None:
00199 self.grasp_pose = geometry_msgs.msg.PoseStamped()
00200 if self.roi_dims is None:
00201 self.roi_dims = geometry_msgs.msg.Vector3()
00202 end = 0
00203 _x = self
00204 start = end
00205 end += 12
00206 (_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00207 start = end
00208 end += 4
00209 (length,) = _struct_I.unpack(str[start:end])
00210 start = end
00211 end += length
00212 if python3:
00213 self.grasp_pose.header.frame_id = str[start:end].decode('utf-8')
00214 else:
00215 self.grasp_pose.header.frame_id = str[start:end]
00216 _x = self
00217 start = end
00218 end += 81
00219 (_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode,) = _struct_10dB.unpack(str[start:end])
00220 return self
00221 except struct.error as e:
00222 raise genpy.DeserializationError(e)
00223
00224 _struct_I = genpy.struct_I
00225 _struct_10dB = struct.Struct("<10dB")
00226 _struct_3I = struct.Struct("<3I")
00227 """autogenerated by genpy from pr2_grasp_adjust/GraspAdjustResponse.msg. Do not edit."""
00228 import sys
00229 python3 = True if sys.hexversion > 0x03000000 else False
00230 import genpy
00231 import struct
00232
00233 import geometry_msgs.msg
00234 import object_manipulation_msgs.msg
00235 import std_msgs.msg
00236
00237 class GraspAdjustResponse(genpy.Message):
00238 _md5sum = "8204d8a3e105f84787abc62e550e0312"
00239 _type = "pr2_grasp_adjust/GraspAdjustResponse"
00240 _has_header = False
00241 _full_text = """geometry_msgs/PoseStamped[] grasp_poses
00242 float64[] pose_scores
00243 float32[] gripper_openings
00244
00245 object_manipulation_msgs/ManipulationResult result
00246
00247
00248
00249 ================================================================================
00250 MSG: geometry_msgs/PoseStamped
00251 # A Pose with reference coordinate frame and timestamp
00252 Header header
00253 Pose pose
00254
00255 ================================================================================
00256 MSG: std_msgs/Header
00257 # Standard metadata for higher-level stamped data types.
00258 # This is generally used to communicate timestamped data
00259 # in a particular coordinate frame.
00260 #
00261 # sequence ID: consecutively increasing ID
00262 uint32 seq
00263 #Two-integer timestamp that is expressed as:
00264 # * stamp.secs: seconds (stamp_secs) since epoch
00265 # * stamp.nsecs: nanoseconds since stamp_secs
00266 # time-handling sugar is provided by the client library
00267 time stamp
00268 #Frame this data is associated with
00269 # 0: no frame
00270 # 1: global frame
00271 string frame_id
00272
00273 ================================================================================
00274 MSG: geometry_msgs/Pose
00275 # A representation of pose in free space, composed of postion and orientation.
00276 Point position
00277 Quaternion orientation
00278
00279 ================================================================================
00280 MSG: geometry_msgs/Point
00281 # This contains the position of a point in free space
00282 float64 x
00283 float64 y
00284 float64 z
00285
00286 ================================================================================
00287 MSG: geometry_msgs/Quaternion
00288 # This represents an orientation in free space in quaternion form.
00289
00290 float64 x
00291 float64 y
00292 float64 z
00293 float64 w
00294
00295 ================================================================================
00296 MSG: object_manipulation_msgs/ManipulationResult
00297 # Result codes for manipulation tasks
00298
00299 # task completed as expected
00300 # generally means you can proceed as planned
00301 int32 SUCCESS = 1
00302
00303 # task not possible (e.g. out of reach or obstacles in the way)
00304 # generally means that the world was not disturbed, so you can try another task
00305 int32 UNFEASIBLE = -1
00306
00307 # task was thought possible, but failed due to unexpected events during execution
00308 # it is likely that the world was disturbed, so you are encouraged to refresh
00309 # your sensed world model before proceeding to another task
00310 int32 FAILED = -2
00311
00312 # a lower level error prevented task completion (e.g. joint controller not responding)
00313 # generally requires human attention
00314 int32 ERROR = -3
00315
00316 # means that at some point during execution we ended up in a state that the collision-aware
00317 # arm navigation module will not move out of. The world was likely not disturbed, but you
00318 # probably need a new collision map to move the arm out of the stuck position
00319 int32 ARM_MOVEMENT_PREVENTED = -4
00320
00321 # specific to grasp actions
00322 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00323 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00324 int32 LIFT_FAILED = -5
00325
00326 # specific to place actions
00327 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00328 # it is likely that the collision environment will see collisions between the hand and the object
00329 int32 RETREAT_FAILED = -6
00330
00331 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00332 int32 CANCELLED = -7
00333
00334 # the actual value of this error code
00335 int32 value
00336
00337 """
00338 __slots__ = ['grasp_poses','pose_scores','gripper_openings','result']
00339 _slot_types = ['geometry_msgs/PoseStamped[]','float64[]','float32[]','object_manipulation_msgs/ManipulationResult']
00340
00341 def __init__(self, *args, **kwds):
00342 """
00343 Constructor. Any message fields that are implicitly/explicitly
00344 set to None will be assigned a default value. The recommend
00345 use is keyword arguments as this is more robust to future message
00346 changes. You cannot mix in-order arguments and keyword arguments.
00347
00348 The available fields are:
00349 grasp_poses,pose_scores,gripper_openings,result
00350
00351 :param args: complete set of field values, in .msg order
00352 :param kwds: use keyword arguments corresponding to message field names
00353 to set specific fields.
00354 """
00355 if args or kwds:
00356 super(GraspAdjustResponse, self).__init__(*args, **kwds)
00357
00358 if self.grasp_poses is None:
00359 self.grasp_poses = []
00360 if self.pose_scores is None:
00361 self.pose_scores = []
00362 if self.gripper_openings is None:
00363 self.gripper_openings = []
00364 if self.result is None:
00365 self.result = object_manipulation_msgs.msg.ManipulationResult()
00366 else:
00367 self.grasp_poses = []
00368 self.pose_scores = []
00369 self.gripper_openings = []
00370 self.result = object_manipulation_msgs.msg.ManipulationResult()
00371
00372 def _get_types(self):
00373 """
00374 internal API method
00375 """
00376 return self._slot_types
00377
00378 def serialize(self, buff):
00379 """
00380 serialize message into buffer
00381 :param buff: buffer, ``StringIO``
00382 """
00383 try:
00384 length = len(self.grasp_poses)
00385 buff.write(_struct_I.pack(length))
00386 for val1 in self.grasp_poses:
00387 _v1 = val1.header
00388 buff.write(_struct_I.pack(_v1.seq))
00389 _v2 = _v1.stamp
00390 _x = _v2
00391 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00392 _x = _v1.frame_id
00393 length = len(_x)
00394 if python3 or type(_x) == unicode:
00395 _x = _x.encode('utf-8')
00396 length = len(_x)
00397 buff.write(struct.pack('<I%ss'%length, length, _x))
00398 _v3 = val1.pose
00399 _v4 = _v3.position
00400 _x = _v4
00401 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00402 _v5 = _v3.orientation
00403 _x = _v5
00404 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00405 length = len(self.pose_scores)
00406 buff.write(_struct_I.pack(length))
00407 pattern = '<%sd'%length
00408 buff.write(struct.pack(pattern, *self.pose_scores))
00409 length = len(self.gripper_openings)
00410 buff.write(_struct_I.pack(length))
00411 pattern = '<%sf'%length
00412 buff.write(struct.pack(pattern, *self.gripper_openings))
00413 buff.write(_struct_i.pack(self.result.value))
00414 except struct.error as se: self._check_types(se)
00415 except TypeError as te: self._check_types(te)
00416
00417 def deserialize(self, str):
00418 """
00419 unpack serialized message in str into this message instance
00420 :param str: byte array of serialized message, ``str``
00421 """
00422 try:
00423 if self.grasp_poses is None:
00424 self.grasp_poses = None
00425 if self.result is None:
00426 self.result = object_manipulation_msgs.msg.ManipulationResult()
00427 end = 0
00428 start = end
00429 end += 4
00430 (length,) = _struct_I.unpack(str[start:end])
00431 self.grasp_poses = []
00432 for i in range(0, length):
00433 val1 = geometry_msgs.msg.PoseStamped()
00434 _v6 = val1.header
00435 start = end
00436 end += 4
00437 (_v6.seq,) = _struct_I.unpack(str[start:end])
00438 _v7 = _v6.stamp
00439 _x = _v7
00440 start = end
00441 end += 8
00442 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00443 start = end
00444 end += 4
00445 (length,) = _struct_I.unpack(str[start:end])
00446 start = end
00447 end += length
00448 if python3:
00449 _v6.frame_id = str[start:end].decode('utf-8')
00450 else:
00451 _v6.frame_id = str[start:end]
00452 _v8 = val1.pose
00453 _v9 = _v8.position
00454 _x = _v9
00455 start = end
00456 end += 24
00457 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00458 _v10 = _v8.orientation
00459 _x = _v10
00460 start = end
00461 end += 32
00462 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00463 self.grasp_poses.append(val1)
00464 start = end
00465 end += 4
00466 (length,) = _struct_I.unpack(str[start:end])
00467 pattern = '<%sd'%length
00468 start = end
00469 end += struct.calcsize(pattern)
00470 self.pose_scores = struct.unpack(pattern, str[start:end])
00471 start = end
00472 end += 4
00473 (length,) = _struct_I.unpack(str[start:end])
00474 pattern = '<%sf'%length
00475 start = end
00476 end += struct.calcsize(pattern)
00477 self.gripper_openings = struct.unpack(pattern, str[start:end])
00478 start = end
00479 end += 4
00480 (self.result.value,) = _struct_i.unpack(str[start:end])
00481 return self
00482 except struct.error as e:
00483 raise genpy.DeserializationError(e)
00484
00485
00486 def serialize_numpy(self, buff, numpy):
00487 """
00488 serialize message with numpy array types into buffer
00489 :param buff: buffer, ``StringIO``
00490 :param numpy: numpy python module
00491 """
00492 try:
00493 length = len(self.grasp_poses)
00494 buff.write(_struct_I.pack(length))
00495 for val1 in self.grasp_poses:
00496 _v11 = val1.header
00497 buff.write(_struct_I.pack(_v11.seq))
00498 _v12 = _v11.stamp
00499 _x = _v12
00500 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00501 _x = _v11.frame_id
00502 length = len(_x)
00503 if python3 or type(_x) == unicode:
00504 _x = _x.encode('utf-8')
00505 length = len(_x)
00506 buff.write(struct.pack('<I%ss'%length, length, _x))
00507 _v13 = val1.pose
00508 _v14 = _v13.position
00509 _x = _v14
00510 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00511 _v15 = _v13.orientation
00512 _x = _v15
00513 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00514 length = len(self.pose_scores)
00515 buff.write(_struct_I.pack(length))
00516 pattern = '<%sd'%length
00517 buff.write(self.pose_scores.tostring())
00518 length = len(self.gripper_openings)
00519 buff.write(_struct_I.pack(length))
00520 pattern = '<%sf'%length
00521 buff.write(self.gripper_openings.tostring())
00522 buff.write(_struct_i.pack(self.result.value))
00523 except struct.error as se: self._check_types(se)
00524 except TypeError as te: self._check_types(te)
00525
00526 def deserialize_numpy(self, str, numpy):
00527 """
00528 unpack serialized message in str into this message instance using numpy for array types
00529 :param str: byte array of serialized message, ``str``
00530 :param numpy: numpy python module
00531 """
00532 try:
00533 if self.grasp_poses is None:
00534 self.grasp_poses = None
00535 if self.result is None:
00536 self.result = object_manipulation_msgs.msg.ManipulationResult()
00537 end = 0
00538 start = end
00539 end += 4
00540 (length,) = _struct_I.unpack(str[start:end])
00541 self.grasp_poses = []
00542 for i in range(0, length):
00543 val1 = geometry_msgs.msg.PoseStamped()
00544 _v16 = val1.header
00545 start = end
00546 end += 4
00547 (_v16.seq,) = _struct_I.unpack(str[start:end])
00548 _v17 = _v16.stamp
00549 _x = _v17
00550 start = end
00551 end += 8
00552 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00553 start = end
00554 end += 4
00555 (length,) = _struct_I.unpack(str[start:end])
00556 start = end
00557 end += length
00558 if python3:
00559 _v16.frame_id = str[start:end].decode('utf-8')
00560 else:
00561 _v16.frame_id = str[start:end]
00562 _v18 = val1.pose
00563 _v19 = _v18.position
00564 _x = _v19
00565 start = end
00566 end += 24
00567 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00568 _v20 = _v18.orientation
00569 _x = _v20
00570 start = end
00571 end += 32
00572 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00573 self.grasp_poses.append(val1)
00574 start = end
00575 end += 4
00576 (length,) = _struct_I.unpack(str[start:end])
00577 pattern = '<%sd'%length
00578 start = end
00579 end += struct.calcsize(pattern)
00580 self.pose_scores = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00581 start = end
00582 end += 4
00583 (length,) = _struct_I.unpack(str[start:end])
00584 pattern = '<%sf'%length
00585 start = end
00586 end += struct.calcsize(pattern)
00587 self.gripper_openings = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00588 start = end
00589 end += 4
00590 (self.result.value,) = _struct_i.unpack(str[start:end])
00591 return self
00592 except struct.error as e:
00593 raise genpy.DeserializationError(e)
00594
00595 _struct_I = genpy.struct_I
00596 _struct_i = struct.Struct("<i")
00597 _struct_4d = struct.Struct("<4d")
00598 _struct_2I = struct.Struct("<2I")
00599 _struct_3d = struct.Struct("<3d")
00600 class GraspAdjust(object):
00601 _type = 'pr2_grasp_adjust/GraspAdjust'
00602 _md5sum = '155f94ed302ff095096df9b37ecc7886'
00603 _request_class = GraspAdjustRequest
00604 _response_class = GraspAdjustResponse