buyer_k_saap.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 auction_common
00014 
00015 # import auxiliar libraries
00016 import random
00017 import math
00018 
00019 # "global" variables (to be referred as global under def fun(something))
00020 winner_id = 'none'
00021 winner_cost = 0
00022 
00023 
00024 #####################################################################################
00025 ## Buyer Service Callback
00026 #####################################################################################
00027 def handle_auction_server_callback(auction_req):
00028 
00029     # update number of messages in parameter server
00030     if rospy.has_param('/num_messages'):
00031         num_messages = rospy.get_param('/num_messages')
00032         num_messages += 2
00033         rospy.set_param('/num_messages', num_messages)
00034 
00035 
00036     # Graph parameters
00037     graph_parameters = eval(rospy.get_param("graph_info"))
00038     N = int(graph_parameters[0])
00039     l = int(graph_parameters[1])
00040     d = int(graph_parameters[2])
00041     r = math.sqrt((d*l*l)/(math.pi*(N-1)))
00042 
00043     print N, l, d, r
00044 
00045     
00046     # Calculate k (number of hop)
00047     node_position = eval(rospy.get_param('~position'))
00048     auctioneer_position = eval(auction_req._connection_header['auctioneer_position'])
00049 
00050     x = float(node_position[0])-float(auctioneer_position[0])
00051     y = float(node_position[1])-float(auctioneer_position[1])
00052     z = float(node_position[2])-float(auctioneer_position[2])
00053     distance_from_node_to_auctioneer = math.sqrt(x*x+y*y+z*z)
00054     k = int(distance_from_node_to_auctioneer/r)
00055 
00056     print distance_from_node_to_auctioneer, k
00057 
00058     
00059     # Create a bid messsage to put an offer for the item in auction_req!    
00060     bid_response = auction_msgs.msg.Bid()
00061     bid_response.header.frame_id = 'base_link' # to be rechecked
00062     bid_response.header.stamp = rospy.Time.now()
00063     bid_response.buyer_id = rospy.get_name()          
00064         
00065     if auction_req.auction_data.metrics == "distance":
00066         # to be given by the cost to go to position of the ocurring event
00067         # the cost for the metrics==distance is calculated using the euclidean
00068         # distance between the parameter position of the node and the task_position
00069         # given in the auction_req
00070         node_position = eval(rospy.get_param('~position'))
00071         x = float(node_position[0])-auction_req.auction_data.task_location.x
00072         y = float(node_position[1])-auction_req.auction_data.task_location.y
00073         z = float(node_position[2])-auction_req.auction_data.task_location.z
00074         bid_response.cost_distance = float(math.sqrt(x*x+y*y+z*z))
00075     else:
00076         rospy.loginfo("Metrics unkown")
00077         bid_response.cost_distance = 999999;
00078 
00079 
00080     print auction_req.auction_data.subject
00081 
00082 
00083     # Check if node is in the k-hops required range
00084     if k < int(auction_req.auction_data.subject):
00085 
00086         # Relay information to neighbour nodes!
00087         neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)
00088         print neighbour_nodes_relay_list
00089            
00090         if neighbour_nodes_relay_list:              
00091 
00092             # Prepare auction information
00093             if auction_req.auction_data.command == 'join_auction':
00094                 role = 'be_buyer'
00095             else:
00096                 role = 'none'
00097             auction_req.sending_node = rospy.get_name()
00098 
00099             # updated nodes_collected
00100             if rospy.has_param('/nodes_collected'):
00101                 auction_req.nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00102                 rospy.set_param('/nodes_collected',auction_req.nodes_collected)
00103             else:
00104                 auction_req.nodes_collected = rospy.get_param('~neighbour_nodes_list')
00105                 
00106 
00107             for node in neighbour_nodes_relay_list:                  
00108 
00109                 # compose service name
00110                 service_path = node+'/auction_server'
00111 
00112                 rospy.wait_for_service(service_path)
00113                 neighbour_node_auction_server = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctionService, headers={ 'auctioneer_position': auctioneer_position})
00114 
00115                 try:
00116                     neighbour_node_bid_response = neighbour_node_auction_server(auction_req)
00117 
00118                     # log bid information from the neighbour node (debug)
00119                     # rospy.loginfo(neighbour_node_bid_response)
00120                 
00121                 except rospy.ServiceException, e:
00122                     rospy.loginfo("Service call failed: %s",e)
00123 
00124 
00125                 if neighbour_node_bid_response.bid_data.cost_distance < bid_response.cost_distance:
00126                     bid_response.buyer_id= neighbour_node_bid_response.bid_data.buyer_id
00127                     bid_response.cost_distance= neighbour_node_bid_response.bid_data.cost_distance
00128                              
00129               
00130     # return best bid
00131     return {'response_info': 'valid'+rospy.get_name(), 'bid_data': bid_response}
00132 ## End handle_buyer_server_callback


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