seller.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 
00003 # configuring PYTHONPATH (By default, this will add the src and lib directory for each of your dependencies to your PYTHONPATH)
00004 import roslib; roslib.load_manifest('sap_pkg')
00005 
00006 # imports to access Master_API
00007 import os, xmlrpclib
00008 
00009 # import client library
00010 import rospy
00011 
00012 # import messages
00013 import auction_msgs.msg
00014 
00015 # import services
00016 import auction_srvs.srv
00017 
00018 # import auxiliar libraries
00019 import random, math, sys
00020 
00021 
00022 ###############################################################################
00023 ## Main function
00024 ###############################################################################
00025 if __name__ == "__main__":
00026         
00027     # initialize node (we will have several nodes, anonymous=True)
00028     rospy.init_node('seller', anonymous=False)
00029 
00030 
00031     # setting message number to zero (if doesn't exists it will be created)
00032     rospy.set_param('/num_messages', 0)    
00033     # clean nodes_collected
00034     rospy.set_param('/nodes_collected', '')    
00035 
00036 
00037     # here we want to unregister services (clean-up procedure)
00038     #rospy.set_param('/auction_closed', False)
00039     
00040     #master_server = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00041     #print master_server.getSystemState(rospy.get_name())
00042     #code, state, uri= master_server.getSystemState(rospy.get_name(),'/node_2/auction_config_server')
00043     #print str(code)+ str(state)+ str(uri)
00044 
00045 
00046     # create auction information
00047     role = 'be_auctioneer'
00048     auction_type = 'sap'
00049     sending_node = rospy.get_name()
00050     nodes_collected = ''
00051   
00052     auction_data = auction_msgs.msg.Auction()
00053     auction_data.header.stamp = rospy.Time.now()
00054     auction_data.header.frame_id = 'base_link'
00055     auction_data.command = 'join_auction'
00056     auction_data.task_type_name = 'goto'
00057     auction_data.subject = 'all'
00058     auction_data.metrics = 'distance'
00059     auction_data.length = rospy.Duration(10)
00060     auction_data.task_location.x = float(sys.argv[1]) #random.random()*100 # l = 100
00061     auction_data.task_location.y = float(sys.argv[2]) #random.random()*100 # l = 100
00062     auction_data.task_location.z = 0
00063 
00064     print auction_data.task_location
00065 
00066 
00067     # evaluate nearest node to event position
00068     event_location = auction_data.task_location
00069     stop_search = False
00070     i = 1
00071     number_of_nodes = 0
00072     nearest_node = []
00073     nearest_node_distance = 99999999
00074     while not stop_search:
00075         try:
00076             node = '/node_'+str(i)
00077             node_param = node+'/position'
00078             node_position = eval(rospy.get_param(node_param))
00079 
00080             # calculate distance to event
00081             x = float(node_position[0])-event_location.x
00082             y = float(node_position[1])-event_location.y
00083             z = float(node_position[2])-event_location.z
00084             distance = float(math.sqrt(x*x+y*y+z*z))
00085 
00086             if distance < nearest_node_distance:
00087                 nearest_node = node
00088                 nearest_node_position = node_position
00089                 nearest_node_distance = distance
00090 
00091             i+=1
00092         except:
00093             rospy.loginfo("Node evaluation complete. Node %s will be auctioneer",nearest_node)
00094             stop_search = True
00095             number_of_nodes = i-1
00096 
00097 
00098     # gettig time to calculate duration of auction
00099     time_i = rospy.Time.now()
00100 
00101 
00102     # prepare to call AuctionConfigService in the node that will be the auctioneer
00103     service_path = nearest_node+'/auction_config_server'
00104     
00105     rospy.wait_for_service(service_path)
00106     auction_config_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctionConfigService)
00107 
00108     try:
00109         auction_config_server_resp = auction_config_service(role,auction_type,sending_node)
00110         rospy.loginfo(auction_config_server_resp)
00111     except rospy.ServiceException, e:
00112         rospy.logwarn("Service did not process request: %s",e)
00113 
00114 
00115     # send the auction information to the auctioneer node using the AuctioneerService
00116     service_path = nearest_node+'/auctioneer_server'   
00117     
00118     rospy.wait_for_service(service_path)
00119     auctioneer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctioneerService)
00120     rospy.loginfo("[message] Seller request")
00121 
00122     try:
00123         auctioneer_server_resp = auctioneer_service(sending_node,nodes_collected,auction_data)
00124         rospy.loginfo("[message] Auctioneer response")
00125         rospy.loginfo(auctioneer_server_resp)
00126     except rospy.ServiceException, e:
00127         rospy.logwarn("Service did not process request: %s",e)
00128 
00129         
00130 
00131 
00132 
00133 
00134 
00135 
00136     # here we want to unregister services (clean-up procedure)
00137     # ATTENTION: here we need to revert the order of calling services, since the call to auction_config_server will shutdown auctioneer services 
00138     rospy.set_param('/auction_closed', True)
00139     """
00140     try:
00141         auction_data.command = 'close_auction'
00142         auctioneer_server_resp = auctioneer_service(sending_node,nodes_collected,auction_data)
00143         rospy.loginfo("[message] Auctioneer response")
00144         rospy.loginfo(auctioneer_server_resp)
00145     except rospy.ServiceException, e:
00146         rospy.logwarn("Service did not process request: %s",e)
00147 
00148     try:
00149         auction_config_server_resp = auction_config_service('none',auction_type,sending_node)
00150         rospy.loginfo(auction_config_server_resp)
00151     except rospy.ServiceException, e:
00152         rospy.logwarn("Service did not process request: %s",e)
00153     """
00154 
00155     """
00156     master_server = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00157     i=1
00158     stop = False
00159     while not stop:
00160         try:
00161             service = '/node_'+str(i)+'/auction_config_server'
00162             print master_server.lookupService(rospy.get_name(),service)
00163             i+=1
00164         except:
00165             stop = True
00166     """    
00167 
00168 
00169     
00170 
00171 
00172 
00173 
00174     # Getting results for statistic studies
00175     # get collected nodes
00176     nodes_collected_list = rospy.get_param('/nodes_collected').split(',')
00177     # remove '' strings
00178     while '' in nodes_collected_list:
00179         nodes_collected_list.remove('')
00180 
00181     # remove duplicates
00182     nodes_collected_list = list(set(nodes_collected_list))    
00183     nodes_collected_str = ','.join(nodes_collected_list)
00184     print 'Computed number of nodes: '+str(number_of_nodes)+' Collected Nodes: '+nodes_collected_str
00185 
00186     # Calculate auction duration
00187     auction_duration = rospy.Time.now() - time_i
00188 
00189     # Obtain average number of messages per robot
00190     if rospy.has_param('/num_messages'):
00191         messages = float(rospy.get_param('/num_messages')/number_of_nodes)
00192         
00193 
00194     # writing results to file   
00195     f = open(sys.argv[3], 'a')
00196     print "i'm getting values from ros parameter server right now and output to file"
00197     line = str(event_location.x)+' '+str(event_location.y)+' '+str(auction_duration.to_sec())+' '+str(messages)+' '+str(auctioneer_server_resp.winner_id)+' '+str(auctioneer_server_resp.winner_cost)+' '+'\n'
00198     print line
00199     #rospy.sleep(1.0)
00200     f.write(line)
00201     f.close()
00202 
00203 
00204    
00205 
00206                                                
00207 ## End main


sap_pkg
Author(s): Joao Manuel Leitao Quintas
autogenerated on Mon Jan 6 2014 11:28:15