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 import auction_common
00014
00015
00016 import random
00017 import math
00018
00019
00020 winner_id = 'none'
00021 winner_cost = 0
00022
00023
00024
00025
00026
00027 def handle_buyer_server_callback(auction_req):
00028
00029
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
00037 bid = auction_msgs.msg.Bid()
00038 bid.header.frame_id = 'base_link'
00039 bid.header.stamp = rospy.Time.now()
00040 bid.buyer_id = rospy.get_name()
00041
00042 if auction_req.auction_data.metrics == "distance":
00043
00044
00045
00046
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.cost_distance = float(math.sqrt(x*x+y*y+z*z))
00052 else:
00053 rospy.loginfo("Metrics unkown")
00054 bid.cost_distance = 999999;
00055
00056
00057 service_path = auction_req.auctioneer_node+'/auctioneer_bid_reception_server'
00058
00059 rospy.wait_for_service(service_path)
00060 auctioneer_bid_reception_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctioneerBidReceptionService)
00061
00062 try:
00063 sending_node = rospy.get_name()
00064 auctioneer_bid_reception_server_resp = auctioneer_bid_reception_service(sending_node,bid)
00065
00066 except rospy.ServiceException, e:
00067 rospy.logwarn("Service did not process request: %s",e)
00068
00069
00070
00071
00072 neighbour_nodes_relay_list = auction_common.create_neighbour_nodes_list(auction_req)
00073
00074 if neighbour_nodes_relay_list:
00075
00076
00077 if auction_req.auction_data.command == 'join_auction':
00078 role = 'be_buyer'
00079 else:
00080 role = 'none'
00081
00082 auction_type = 'sap'
00083 sending_node = rospy.get_name()
00084
00085 auctioneer_node = auction_req.auctioneer_node
00086
00087
00088 if rospy.has_param('/nodes_collected'):
00089 nodes_collected = rospy.get_param('/nodes_collected')+','+rospy.get_name()
00090 rospy.set_param('/nodes_collected',nodes_collected)
00091 else:
00092 nodes_collected = rospy.get_param('~neighbour_nodes_list')
00093
00094 auction_data = auction_req.auction_data
00095
00096
00097 for node in neighbour_nodes_relay_list:
00098
00099
00100 service_path = node+'/auction_config_server'
00101
00102 rospy.wait_for_service(service_path)
00103 neighbour_node_auction_config_server = rospy.ServiceProxy(service_path,
00104 auction_srvs.srv.AuctionConfigService)
00105
00106 try:
00107 neighbour_node_auction_config_server_resp = neighbour_node_auction_config_server(role,auction_type,sending_node)
00108
00109 except rospy.ServiceException, e:
00110 rospy.logwarn("[%s] Service call failed: %s",rospy.get_name(),e)
00111
00112
00113
00114 service_path = node+'/buyer_server'
00115
00116 rospy.wait_for_service(service_path)
00117 buyer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.BuyerService)
00118
00119 try:
00120 buyer_server_resp = buyer_service(auctioneer_node,sending_node,nodes_collected,auction_data)
00121
00122 except rospy.ServiceException, e:
00123 rospy.logwarn("[%s] Service call failed: %s",rospy.get_name(),e)
00124
00125
00126
00127
00128 return {'response_info': 'valid'+rospy.get_name()}