buyer_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('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     # Create a bid messsage to put an offer for the item in auction_req!    
00037     bid_response = auction_msgs.msg.Bid()
00038     bid_response.header.frame_id = 'base_link' # to be rechecked
00039     bid_response.header.stamp = rospy.Time.now()
00040     bid_response.buyer_id = rospy.get_name()          
00041         
00042     if auction_req.auction_data.metrics == "distance":
00043         # to be given by the cost to go to position of the ocurring event
00044         # the cost for the metrics==distance is calculated using the euclidean
00045         # distance between the parameter position of the node and the task_position
00046         # given in the auction_req
00047         node_position = eval(rospy.get_param('~position'))
00048         x = float(node_position[0])-auction_req.auction_data.task_location.x
00049         y = float(node_position[1])-auction_req.auction_data.task_location.y
00050         z = float(node_position[2])-auction_req.auction_data.task_location.z
00051         bid_response.cost_distance = float(math.sqrt(x*x+y*y+z*z))
00052     else:
00053         rospy.loginfo("Metrics unkown")
00054         bid_response.cost_distance = 999999;
00055 
00056 
00057     # Relay information to neighbour nodes!
00058     neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)
00059            
00060     if neighbour_nodes_relay_list:              
00061 
00062         # Prepare auction information
00063         if auction_req.auction_data.command == 'join_auction':
00064             role = 'be_buyer'
00065         else:
00066             role = 'none'
00067         auction_req.sending_node = rospy.get_name()
00068 
00069         # updated nodes_collected
00070         if rospy.has_param('/nodes_collected'):
00071             auction_req.nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00072             rospy.set_param('/nodes_collected',auction_req.nodes_collected)
00073         else:
00074             auction_req.nodes_collected = rospy.get_param('~neighbour_nodes_list')
00075 
00076         # call the Auction Service from each neighbour of the node
00077         for node in neighbour_nodes_relay_list:                  
00078             # obtain response from neighbour buyer node (in k=1)                 
00079             bid_response_neighbour_node = auction_common.neighbour_node_auction_client(node,auction_req)
00080             
00081             if bid_response_neighbour_node.cost_distance < bid_response.cost_distance:
00082                 bid_response.buyer_id= bid_response_neighbour_node.buyer_id
00083                 bid_response.cost_distance= bid_response_neighbour_node.cost_distance
00084                              
00085               
00086     # return best bid
00087     return {'response_info': 'valid'+rospy.get_name(), 'bid_data':bid_response}


saap_pkg
Author(s): Joao Manuel Leitao Quintas
autogenerated on Mon Jan 6 2014 11:26:19