auction_common.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 auxiliar libraries
00014 import random
00015 import math
00016 
00017 # "global" variables (to be referred as global under def fun(something))
00018 winner_id = 'none'
00019 winner_cost = 0
00020 
00021 role_assigned = False
00022 node_role = 'none'
00023 
00024 
00025 ################################################################################
00026 ## Auction Client for Neighbour Nodes 
00027 ## (to be called in the node to pass data to its neighbours)
00028 ################################################################################
00029 def neighbour_node_auction_client(neighbour_node, auction_req):
00030 
00031     # compose service name (to be changed)
00032     service_path = neighbour_node+'/auction_server'
00033 
00034     # wait for the service in the neighbour node to be available
00035     rospy.wait_for_service(service_path)
00036 
00037     try:
00038         # create the handle to the service client in the neighbour node
00039         neighbour_node_auction_server = rospy.ServiceProxy(service_path,
00040                                                            auction_srvs.srv.AuctionService)
00041 
00042         # call the service with the current auction information as input parameter
00043         neighbour_node_bid_response = neighbour_node_auction_server(auction_req)
00044 
00045         # log bid information from the neighbour node (debug)
00046         #rospy.loginfo(neighbour_node_bid_response)
00047 
00048         # return the bid into the parent/calling node
00049         #return {'response_info':'valid','bid_data':neighbour_node_bid_response}
00050         return neighbour_node_bid_response.bid_data
00051         
00052     except rospy.ServiceException, e:
00053         rospy.loginfo("Service call failed: %s",e)
00054             
00055 ## End neighbour_node_auction_client
00056 
00057 
00058 
00059 
00060 #########################################################################################
00061 ## Create list of neighbour nodes to relay the auction_req
00062 ## (must return a list)
00063 #########################################################################################
00064 def create_neighbour_nodes_list(auction_req):
00065 
00066     neighbour_nodes_string = rospy.get_param('~neighbour_nodes_list')
00067     neighbour_nodes_list = neighbour_nodes_string.split(',')
00068 
00069     ##debug##
00070     #print "1."
00071     #print neighbour_nodes_list
00072     #for node in neighbour_nodes_list:
00073     #    print node
00074     ##debug##
00075 
00076     #print neighbour_nodes_string
00077     #print auction_req.nodes_collected
00078 
00079     #nodes_collected_list = neighbour_nodes_list + auction_req.nodes_collected.split(',')
00080     #print "Collected nodes list:"
00081     #print nodes_collected_list
00082 
00083     # print "Intersection:"
00084     # print list(set(neighbour_nodes_list) & set(auction_req.nodes_collected.split(',')))
00085     # print "Union:"
00086     # print list(set(neighbour_nodes_list) | set(auction_req.nodes_collected.split(',')))
00087     # print "Difference"
00088     # print list(set(neighbour_nodes_list) - set(auction_req.nodes_collected.split(',')))
00089 
00090     nodes_collected_list = list(set(neighbour_nodes_list) - set(auction_req.nodes_collected.split(',')))
00091     
00092 
00093     # remove '' strings
00094     while '' in nodes_collected_list:
00095         nodes_collected_list.remove('')
00096 
00097     # remove duplicates
00098     nodes_collected_list = list(set(nodes_collected_list))
00099     
00100     # remove self-references
00101     while rospy.get_name() in nodes_collected_list:
00102         nodes_collected_list.remove(rospy.get_name())
00103 
00104     # remove references to the sender node
00105     while auction_req.sending_node in nodes_collected_list:
00106         nodes_collected_list.remove(auction_req.sending_node)
00107         
00108 
00109     if nodes_collected_list:
00110 
00111         # convert list to string splited by ','
00112         nodes_collected_string = ','.join(nodes_collected_list)
00113 
00114         ##debug##
00115         #print "\nNodes Collected:"+nodes_collected_string+"\n"
00116         ##debug##
00117 
00118         neighbour_nodes_list = nodes_collected_string.split(',')
00119 
00120     else:
00121         neighbour_nodes_list = []
00122         pass
00123 
00124     return neighbour_nodes_list
00125     #return nodes_collected_list
00126 
00127 ## End create_neighbour_nodes_list


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