auctioneer.py
Go to the documentation of this file.
00001 # configuring PYTHONPATH (By default, this will add the src and lib directory for each of your dependencies to your PYTHONPATH)
00002 import roslib; roslib.load_manifest('k-saap_pkg')
00003 
00004 # import client library
00005 import rospy
00006 
00007 # import messages
00008 import auction_msgs.msg
00009 
00010 # import services
00011 import auction_srvs.srv
00012 
00013 # import services functions
00014 import auction_common
00015 
00016 # import auxiliar libraries
00017 import random
00018 import math
00019 
00020 # "global" variables (to be referred as global under def fun(something))
00021 winner_id = ''
00022 winner_cost = 999999
00023 
00024 
00025 #####################################################################################
00026 ## Auction Service (Server Callback)
00027 #####################################################################################
00028 def handle_auction_server_callback(auction_req):
00029 
00030     # define global variables
00031     global winner_id
00032     global winner_cost    
00033 
00034 
00035     # update number of messages in parameter server
00036     if rospy.has_param('/num_messages'):
00037         num_messages = rospy.get_param('/num_messages')
00038         num_messages += 2
00039         rospy.set_param('/num_messages', num_messages)
00040 
00041 
00042     # default bid
00043     bid = auction_msgs.msg.Bid()
00044 
00045     # obtain auctioneer_position
00046     auctioneer_position = {'auctioneer_position': rospy.get_param('~position')}    
00047         
00048     # Obtain nodes list to relay information with k=1
00049     neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)        
00050     print neighbour_nodes_relay_list
00051         
00052     # Prepare auction information
00053     if auction_req.auction_data.command == 'close_auction':
00054         auction_req.role = 'none'
00055     else:
00056         auction_req.role = "be_buyer"    
00057 
00058     auction_req.sending_node = rospy.get_name()
00059 
00060     # updated nodes_collected
00061     if rospy.has_param('/nodes_collected'):
00062         auction_req.nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00063         rospy.set_param('/nodes_collected',auction_req.nodes_collected)
00064     else:
00065         auction_req.nodes_collected = rospy.get_param('~neighbour_nodes_list')
00066     
00067             
00068     # Call the Auction Service from each neighbour node
00069     for node in neighbour_nodes_relay_list:
00070 
00071         # compose service name (to be changed)
00072         service_path = node+'/auction_server'
00073 
00074         # wait for the service in the neighbour node to be available
00075         rospy.wait_for_service(service_path)
00076         neighbour_node_auction_server = rospy.ServiceProxy(service_path,
00077                                                            auction_srvs.srv.AuctionService,headers=auctioneer_position)
00078 
00079         try:
00080             bid_response = neighbour_node_auction_server(auction_req)
00081 
00082             bid = bid_response.bid_data
00083 
00084             # Evaluate bids, Min(cost_distance)    
00085             if winner_cost >= bid.cost_distance:
00086                 if bid.buyer_id != '':
00087                     winner_cost = bid.cost_distance
00088                     winner_id = bid.buyer_id
00089                 
00090             # log info for momentary winner
00091             # rospy.loginfo("(winning at the moment) %s with offer %d",winner_id, winner_cost)
00092                     
00093         except rospy.ServiceException, e:
00094             rospy.loginfo("Service call failed: %s",e)
00095 
00096                 
00097     # verbose for auction status (received all the bids)
00098     rospy.loginfo("winner was: %s with offer %d",winner_id, winner_cost)
00099 
00100     # return response
00101     # return auction_srvs.srv.AuctionServiceResponse(bid_response)
00102     return {'response_info': 'valid', 'bid_data': bid}
00103 ## End Auction Server (Server Callback)


k-saap_pkg
Author(s): Joao Manuel Leitao Quintas
autogenerated on Mon Jan 6 2014 11:29:06