Go to the documentation of this file.00001 
00002 
00003 
00004 import roslib; roslib.load_manifest('saap_pkg')
00005 
00006 
00007 import os, xmlrpclib
00008 
00009 
00010 import rospy
00011 
00012 
00013 import auction_msgs.msg
00014 
00015 
00016 import auction_srvs.srv
00017 
00018 
00019 import random, math, sys
00020 
00021 
00022 
00023 
00024 
00025 if __name__ == "__main__":
00026         
00027     
00028     rospy.init_node('seller', anonymous=False)
00029 
00030     
00031     rospy.set_param('/num_messages', 0)
00032     
00033     rospy.set_param('/nodes_collected', '')  
00034 
00035     
00036     role = 'be_auctioneer'
00037     auction_type = 'saap'
00038     sending_node = rospy.get_name()
00039     nodes_collected = ''
00040   
00041     auction_data = auction_msgs.msg.Auction()
00042     auction_data.header.stamp = rospy.Time.now()
00043     auction_data.header.frame_id = 'base_link'
00044     auction_data.command = 'join_auction'
00045     auction_data.task_type_name = 'goto'
00046     auction_data.subject = 'all'
00047     auction_data.metrics = 'distance'
00048     auction_data.length = rospy.Duration(10)
00049     auction_data.task_location.x = float(sys.argv[1]) 
00050     auction_data.task_location.y = float(sys.argv[2]) 
00051     auction_data.task_location.z = 0
00052 
00053     print auction_data.task_location
00054 
00055 
00056     
00057     event_location = auction_data.task_location
00058     stop_search = False
00059     i = 1
00060     number_of_nodes = 0
00061     nearest_node = []
00062     nearest_node_distance = 99999999
00063     while not stop_search:
00064         try:
00065             node = '/node_'+str(i)
00066             node_param = node+'/position'
00067             node_position = eval(rospy.get_param(node_param))
00068 
00069             
00070             x = float(node_position[0])-event_location.x
00071             y = float(node_position[1])-event_location.y
00072             z = float(node_position[2])-event_location.z
00073             distance = float(math.sqrt(x*x+y*y+z*z))
00074 
00075             if distance < nearest_node_distance:
00076                 nearest_node = node
00077                 nearest_node_position = node_position
00078                 nearest_node_distance = distance
00079 
00080             i+=1
00081         except:
00082             print "Node evaluation complete. Node %s will be auctioneer"%nearest_node
00083             stop_search = True
00084             number_of_nodes = i-1
00085 
00086 
00087     
00088     time_i = rospy.Time.now()
00089 
00090 
00091     
00092     service_path = nearest_node+'/auction_server'
00093 
00094     rospy.wait_for_service(service_path)
00095     auctioneer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctionService)
00096 
00097     try:
00098         auctioneer_service_resp = auctioneer_service(role,auction_type,sending_node,nodes_collected,auction_data)
00099         rospy.loginfo("[message] Auctioneer response")
00100         rospy.loginfo(auctioneer_service_resp)
00101     except rospy.ServiceException, e:
00102          rospy.logwarn("Service did not process request: %s",e)
00103 
00104 
00105 
00106 
00107     
00108     
00109     rospy.set_param('/auction_closed', True)
00110 
00111 
00112 
00113 
00114     
00115     
00116     nodes_collected_list = rospy.get_param('/nodes_collected').split(',')
00117     
00118     while '' in nodes_collected_list:
00119         nodes_collected_list.remove('')
00120 
00121     
00122     nodes_collected_list = list(set(nodes_collected_list))    
00123     nodes_collected_str = ','.join(nodes_collected_list)
00124     print 'Computed number of nodes: '+str(number_of_nodes)+' Collected Nodes: '+nodes_collected_str
00125 
00126     
00127     auction_duration = rospy.Time.now() - time_i
00128 
00129     
00130     if rospy.has_param('/num_messages'):
00131         messages = float(rospy.get_param('/num_messages')/number_of_nodes)
00132         
00133 
00134     
00135     f = open(sys.argv[3], 'a')
00136     print "i'm getting values from ros parameter server right now and output to file"
00137     line = str(event_location.x)+' '+str(event_location.y)+' '+str(auction_duration.to_sec())+' '+str(messages)+' '+str(auctioneer_service_resp.bid_data.buyer_id)+' '+str(auctioneer_service_resp.bid_data.cost_distance)+' '+'\n'
00138     f.write(line)
00139     f.close()
00140 
00141                                                      
00142