Go to the documentation of this file.00001 
00002 import roslib; roslib.load_manifest('saap_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_auction_server_callback(auction_req):
00029 
00030     
00031     global winner_id
00032     global winner_cost    
00033 
00034     
00035     if rospy.has_param('/num_messages'):
00036         num_messages = rospy.get_param('/num_messages')
00037         num_messages += 2
00038         rospy.set_param('/num_messages', num_messages)
00039 
00040 
00041     
00042     if auction_req.auction_data.command == 'close_auction':
00043         auction_req.role = 'none'
00044         
00045         
00046         
00047 
00048     elif auction_req.auction_data.command == 'join_auction':         
00049         
00050         
00051         neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)        
00052         
00053         
00054         auction_req.sending_node = rospy.get_name()
00055 
00056 
00057         
00058         if rospy.has_param('/nodes_collected'):
00059             auction_req.nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00060             rospy.set_param('/nodes_collected',auction_req.nodes_collected)
00061         else:
00062             auction_req.nodes_collected = rospy.get_param('~neighbour_nodes_list')
00063 
00064 
00065         auction_req.role = "be_buyer"
00066             
00067         
00068         for node in neighbour_nodes_relay_list:
00069             
00070             bid_response = auction_common.neighbour_node_auction_client(node, auction_req)
00071 
00072             
00073             if winner_cost >= bid_response.cost_distance:
00074                 if bid_response.buyer_id != '':
00075                     winner_cost = bid_response.cost_distance
00076                     winner_id = bid_response.buyer_id
00077                 
00078                 
00079                 
00080                 
00081         
00082         rospy.loginfo("winner was: %s with offer %d",winner_id, winner_cost)
00083 
00084         """
00085         # (close auction and inform winner) 
00086         # (client to neighbour nodes with close_auction req)
00087         # (in close_auction req the nodes reset their roles!!)
00088         
00089         # Change the command in auction_req to be sent to neighbour nodes
00090         auction_req.auction_data.command = "close_auction"
00091                 
00092         # Call the Auction Service Reset from each neighbour node
00093         for node in neighbour_nodes_relay_list:
00094                 
00095             # obtain response from neighbour buyer node (in k=1), relaying auction_req
00096             reset_response = auction_common.neighbour_node_auction_client(node, auction_req)
00097 
00098             # Ok, now we can reset our role
00099             role_assigned = False
00100             node_role = 'none'
00101             
00102             
00103         return {'response_info': 'valid', 'bid_data':bid_response}
00104         """           
00105     
00106     
00107     return {'response_info': 'valid', 'bid_data':bid_response}
00108