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('k-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     # setting message number to zero (if doesn't exists it will be created)
00031     rospy.set_param('/num_messages', 0)
00032     # clean nodes_collected
00033     rospy.set_param('/nodes_collected', '') 
00034 
00035 
00036 
00037     # create auction information
00038     role = 'be_auctioneer'
00039     auction_type = 'k-sap'
00040     sending_node = rospy.get_name()
00041     nodes_collected = ''
00042   
00043     auction_data = auction_msgs.msg.Auction()
00044     auction_data.header.stamp = rospy.Time.now()
00045     auction_data.header.frame_id = 'base_link'
00046     auction_data.command = 'join_auction'
00047     auction_data.task_type_name = 'goto'
00048     auction_data.subject = sys.argv[4]
00049     auction_data.metrics = 'distance'
00050     auction_data.length = rospy.Duration(10)
00051     auction_data.task_location.x = float(sys.argv[1]) #random.random()*100 # l = 100
00052     auction_data.task_location.y = float(sys.argv[2]) #random.random()*100 # l = 100
00053     auction_data.task_location.z = 0
00054 
00055     print auction_data.task_location
00056 
00057 
00058     # evaluate nearest node to event position
00059     event_location = auction_data.task_location
00060     stop_search = False
00061     i = 1
00062     number_of_nodes = 0
00063     nearest_node = []
00064     nearest_node_distance = 99999999
00065     while not stop_search:
00066         try:
00067             node = '/node_'+str(i)
00068             node_param = node+'/position'
00069             node_position = eval(rospy.get_param(node_param))
00070 
00071             # calculate distance to event
00072             x = float(node_position[0])-event_location.x
00073             y = float(node_position[1])-event_location.y
00074             z = float(node_position[2])-event_location.z
00075             distance = float(math.sqrt(x*x+y*y+z*z))
00076 
00077             if distance < nearest_node_distance:
00078                 nearest_node = node
00079                 nearest_node_position = node_position
00080                 nearest_node_distance = distance
00081 
00082             i+=1
00083         except:
00084             rospy.loginfo("Node evaluation complete. Node %s will be auctioneer",nearest_node)
00085             stop_search = True
00086             number_of_nodes = i-1
00087 
00088 
00089     # gettig time to calculate duration of auction
00090     time_i = rospy.Time.now()
00091 
00092 
00093     # prepare to call AuctionConfigService in the node that will be the auctioneer
00094     service_path = nearest_node+'/auction_config_server'  
00095     
00096     rospy.wait_for_service(service_path)
00097     auctioneer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctionConfigService)
00098 
00099     try:
00100         auction_config_server_resp = auctioneer_service(role,auction_type,sending_node)
00101         rospy.loginfo(auction_config_server_resp)
00102     except rospy.ServiceException, e:
00103         rospy.logwarn("Service did not process request: %s",e)
00104 
00105 
00106     # send the auction information to the auctioneer node using the AuctioneerService
00107     service_path = nearest_node+'/auctioneer_server'   
00108     
00109     rospy.wait_for_service(service_path)
00110     auctioneer_service = rospy.ServiceProxy(service_path, auction_srvs.srv.AuctioneerService)
00111     rospy.loginfo("[message] Seller request")
00112 
00113     try:
00114         auctioneer_server_resp = auctioneer_service(sending_node,nodes_collected,auction_data)
00115         rospy.loginfo("[message] Auctioneer response")
00116         rospy.loginfo(auctioneer_server_resp)
00117     except rospy.ServiceException, e:
00118         rospy.logwarn("Service did not process request: %s",e)
00119 
00120 
00121 
00122 
00123 
00124 
00125 
00126 
00127     # here we want to unregister services (clean-up procedure)
00128     # ATTENTION: here we need to revert the order of calling services, since the call to auction_config_server will shutdown auctioneer services 
00129     rospy.set_param('/auction_closed', True)
00130     """
00131     try:
00132         auction_data.command = 'close_auction'
00133         auctioneer_server_resp = auctioneer_service(sending_node,nodes_collected,auction_data)
00134         rospy.loginfo("[message] Auctioneer response")
00135         rospy.loginfo(auctioneer_server_resp)
00136     except rospy.ServiceException, e:
00137         rospy.logwarn("Service did not process request: %s",e)
00138 
00139     try:
00140         auction_config_server_resp = auction_config_service('none',auction_type,sending_node)
00141         rospy.loginfo(auction_config_server_resp)
00142     except rospy.ServiceException, e:
00143         rospy.logwarn("Service did not process request: %s",e)
00144     """
00145 
00146     """
00147     master_server = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00148     i=1
00149     stop = False
00150     while not stop:
00151         try:
00152             service = '/node_'+str(i)+'/auction_config_server'
00153             print master_server.lookupService(rospy.get_name(),service)
00154             i+=1
00155         except:
00156             stop = True
00157     """    
00158 
00159 
00160 
00161 
00162 
00163 
00164 
00165     # Getting results for statistic studies
00166     # get collected nodes
00167     nodes_collected_list = rospy.get_param('/nodes_collected').split(',')
00168     # remove '' strings
00169     while '' in nodes_collected_list:
00170         nodes_collected_list.remove('')
00171 
00172     # remove duplicates
00173     nodes_collected_list = list(set(nodes_collected_list))    
00174     nodes_collected_str = ','.join(nodes_collected_list)
00175     print 'Computed number of nodes: '+str(number_of_nodes)+' Collected Nodes: '+nodes_collected_str
00176 
00177     # Calculate auction duration
00178     auction_duration = rospy.Time.now() - time_i
00179 
00180     # Obtain average number of messages per robot
00181     if rospy.has_param('/num_messages'):
00182         messages = float(rospy.get_param('/num_messages')/number_of_nodes)
00183         
00184 
00185     # writing results to file   
00186     f = open(sys.argv[3], 'a')
00187     print "i'm getting values from ros parameter server right now and output to file"
00188     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'
00189     print line
00190     f.write(line)
00191     f.close()
00192 
00193 
00194 
00195 
00196 
00197                                                      
00198 ## End main


k-sap_pkg
Author(s): Joao Manuel Leitao Quintas
autogenerated on Mon Jan 6 2014 11:25:40