Go to the documentation of this file.00001
00002 import roslib; roslib.load_manifest('k-sap_pkg')
00003
00004
00005 import rospy
00006
00007
00008 import auction_msgs.msg
00009
00010
00011 import auction_srvs.srv
00012
00013 import auction_common
00014
00015
00016 import random
00017 import math
00018
00019
00020
00021
00022
00023
00024 def handle_buyer_server_callback(auction_req):
00025
00026
00027 if rospy.has_param('/num_messages'):
00028 num_messages = rospy.get_param('/num_messages')
00029 num_messages += 2
00030 rospy.set_param('/num_messages', num_messages)
00031
00032
00033
00034 graph_parameters = eval(rospy.get_param("graph_info"))
00035 N = int(graph_parameters[0])
00036 l = int(graph_parameters[1])
00037 d = int(graph_parameters[2])
00038 r = math.sqrt((d*l*l)/(math.pi*(N-1)))
00039
00040 print N, l, d, r
00041
00042
00043
00044 node_position = eval(rospy.get_param('~position'))
00045 auctioneer_position = eval(auction_req._connection_header['auctioneer_position'])
00046 x = float(node_position[0])-float(auctioneer_position[0])
00047 y = float(node_position[1])-float(auctioneer_position[1])
00048 z = float(node_position[2])-float(auctioneer_position[2])
00049 distance_from_node_to_auctioneer = math.sqrt(x*x+y*y+z*z)
00050 k = int(distance_from_node_to_auctioneer/r)
00051
00052 print distance_from_node_to_auctioneer, k
00053
00054
00055
00056 bid = auction_msgs.msg.Bid()
00057 bid.header.frame_id = 'base_link'
00058 bid.header.stamp = rospy.Time.now()
00059 bid.buyer_id = rospy.get_name()
00060
00061 if auction_req.auction_data.metrics == "distance":
00062
00063
00064
00065
00066 x = float(node_position[0])-auction_req.auction_data.task_location.x
00067 y = float(node_position[1])-auction_req.auction_data.task_location.y
00068 z = float(node_position[2])-auction_req.auction_data.task_location.z
00069 bid.cost_distance = float(math.sqrt(x*x+y*y+z*z))
00070 else:
00071 rospy.loginfo("Metrics unkown")
00072 bid.cost_distance = 999999;
00073
00074
00075 service_path = auction_req.auctioneer_node+'/auctioneer_bid_reception_server'
00076
00077 rospy.wait_for_service(service_path)
00078 auctioneer_bid_reception_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctioneerBidReceptionService)
00079
00080 try:
00081 sending_node = rospy.get_name()
00082 auctioneer_bid_reception_server_resp = auctioneer_bid_reception_service(sending_node,bid)
00083
00084 except rospy.ServiceException, e:
00085 print "Service did not process request: %s"%str(e)
00086
00087
00088 print int(auction_req.auction_data.subject)
00089
00090
00091 if k < int(auction_req.auction_data.subject):
00092
00093
00094 neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)
00095
00096 if neighbour_nodes_relay_list:
00097
00098
00099 if auction_req.auction_data.command == 'join_auction':
00100 role = "be_buyer"
00101 else:
00102 role = 'none'
00103
00104 auction_type = 'k-sap'
00105 sending_node = rospy.get_name()
00106
00107 auctioneer_node = auction_req.auctioneer_node
00108
00109
00110 if rospy.has_param('/nodes_collected'):
00111 nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00112 rospy.set_param('/nodes_collected',nodes_collected)
00113 else:
00114 nodes_collected = rospy.get_param('~neighbour_nodes_list')
00115
00116 auction_data = auction_req.auction_data
00117
00118 for node in neighbour_nodes_relay_list:
00119
00120
00121 service_path = node+'/auction_config_server'
00122
00123 rospy.wait_for_service(service_path)
00124 neighbour_node_auction_config_server = rospy.ServiceProxy(service_path,
00125 auction_srvs.srv.AuctionConfigService)
00126
00127 try:
00128 neighbour_node_auction_config_server_resp = neighbour_node_auction_config_server(role,auction_type,sending_node)
00129
00130 except rospy.ServiceException, e:
00131 rospy.loginfo("Service call failed: %s",e)
00132
00133
00134
00135 service_path = node+'/buyer_server'
00136
00137 rospy.wait_for_service(service_path)
00138 buyer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.BuyerService, headers= { 'auctioneer_position': auction_req._connection_header['auctioneer_position']})
00139
00140 try:
00141 buyer_server_resp = buyer_service(auctioneer_node,sending_node,nodes_collected,auction_data)
00142
00143 except rospy.ServiceException, e:
00144 print "Service did not process request: %s"%str(e)
00145
00146
00147
00148
00149 return {'response_info': 'valid'+rospy.get_name()}
00150