Go to the documentation of this file.00001
00002 import roslib; roslib.load_manifest('sap_pkg')
00003
00004
00005 import rospy
00006
00007
00008 import auction_msgs.msg
00009
00010
00011 import auction_srvs.srv
00012
00013
00014 import auction_common
00015
00016
00017 import random
00018 import math
00019
00020
00021 winner_id = ''
00022 winner_cost = 999999
00023
00024
00025
00026
00027
00028 def handle_auctioneer_bid_reception_server_callback(bid_req):
00029
00030
00031 global winner_id
00032 global winner_cost
00033
00034
00035 if winner_cost >= bid_req.bid_data.cost_distance:
00036 if bid_req.bid_data.buyer_id != '':
00037 winner_cost = bid_req.bid_data.cost_distance
00038 winner_id = bid_req.bid_data.buyer_id
00039
00040 return {'response_info':'bid_received'}
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050 def handle_auctioneer_server_callback(auction_req):
00051
00052
00053 global winner_id
00054 global winner_cost
00055
00056
00057
00058 if rospy.has_param('/num_messages'):
00059 num_messages = rospy.get_param('/num_messages')
00060 num_messages += 2
00061 rospy.set_param('/num_messages', num_messages)
00062
00063
00064
00065 neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)
00066
00067
00068
00069 if auction_req.auction_data.command == 'join_auction':
00070 role = "be_buyer"
00071 else:
00072 role = 'none'
00073
00074 auction_type = 'sap'
00075 sending_node = rospy.get_name()
00076
00077 auctioneer_node = rospy.get_name()
00078
00079
00080 if rospy.has_param('/nodes_collected'):
00081 nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00082 rospy.set_param('/nodes_collected',nodes_collected)
00083 else:
00084 nodes_collected = rospy.get_param('~neighbour_nodes_list')
00085
00086 auction_data = auction_req.auction_data
00087
00088
00089
00090 for node in neighbour_nodes_relay_list:
00091
00092
00093 service_path = node+'/auction_config_server'
00094
00095 rospy.wait_for_service(service_path)
00096 neighbour_node_auction_config_server = rospy.ServiceProxy(service_path,
00097 auction_srvs.srv.AuctionConfigService)
00098
00099 try:
00100 neighbour_node_auction_config_server_resp = neighbour_node_auction_config_server(role,auction_type,sending_node)
00101
00102 except rospy.ServiceException, e:
00103 rospy.logwarn("[%s] Service call failed: %s",rospy.get_name(),e)
00104
00105
00106
00107 service_path = node+'/buyer_server'
00108
00109 rospy.wait_for_service(service_path)
00110 buyer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.BuyerService)
00111
00112 try:
00113 buyer_server_resp = buyer_service(auctioneer_node,sending_node,nodes_collected,auction_data)
00114
00115 except rospy.ServiceException, e:
00116 rospy.logwarn("Service did not process request: %s",e)
00117
00118
00119
00120 rospy.loginfo("winner was: %s with offer %d",winner_id, winner_cost)
00121
00122
00123
00124
00125
00126 return{'response_info': 'valid','winner_id': winner_id,'winner_cost': winner_cost}
00127