$search
00001 #!/usr/bin/python 00002 00003 import roslib 00004 roslib.load_manifest('srs_assisted_detection') 00005 00006 #from srs_grasping.srv import * 00007 from geometry_msgs.msg import * 00008 00009 from sensor_msgs.msg import * 00010 from srs_assisted_detection.srv import * 00011 from geometry_msgs.msg import * 00012 00013 00014 import rospy 00015 detect=UiDetectorResponse() 00016 func=0 00017 pose=Pose() 00018 action='' 00019 def answerObjectSrv(req): 00020 00021 rospy.loginfo("Get Object information") 00022 00023 global func 00024 func=1 00025 00026 00027 #save 00028 00029 00030 #send action only grasp at the moment 00031 00032 global pose 00033 pose.position.x=detect.object_list.detections[req.id].pose.pose.position.x 00034 pose.position.y=detect.object_list.detections[req.id].pose.pose.position.y 00035 pose.position.z=detect.object_list.detections[req.id].pose.pose.position.z 00036 pose.orientation.x=detect.object_list.detections[req.id].pose.pose.orientation.x 00037 pose.orientation.y=detect.object_list.detections[req.id].pose.pose.orientation.y 00038 pose.orientation.z=detect.object_list.detections[req.id].pose.pose.orientation.z 00039 pose.orientation.w=detect.object_list.detections[req.id].pose.pose.orientation.w 00040 global action 00041 00042 #default for user 00043 action='grasp' 00044 00045 s.shutdown() 00046 s2.shutdown() 00047 moveBB=UiAnswerResponse() 00048 moveBB.message.data='get data waiting for action' 00049 return moveBB 00050 00051 00052 00053 00054 def moveBBSrv(req): 00055 rospy.loginfo("Get BB information") 00056 00057 #BBmove service base and then movement 00058 moveBB=BBMoveResponse() 00059 moveBB.message.data='moving to better position' 00060 global func 00061 func=2 00062 00063 global pose 00064 pose.position.x=1 00065 pose.position.y=2 00066 pose.position.z=3 00067 00068 s.shutdown() 00069 s2.shutdown() 00070 return moveBB 00071 00072 00073 00074 00075 00076 def assisted_answer_server(detections): 00077 #rospy.init_node('asisted_answer_server') 00078 global detect 00079 detect=detections 00080 global s 00081 global s2 00082 s = rospy.Service('assisted_answer', UiAnswer, answerObjectSrv) 00083 s2 = rospy.Service('assisted_BBmove', BBMove, moveBBSrv) 00084 00085 rospy.loginfo("Assisted answer ready.") 00086 s.spin() 00087 s2.spin() 00088 return [func,pose,action] 00089 if __name__ == "__main__": 00090 assisted_answer_server('test')