node.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 
00003 # Each node in the network can:
00004 #   - be called to serve as actioneer or buyer;
00005 #   - actioneer service is called by a seller/collector node with 
00006 #     request start_auction;
00007 #   - buyer service is called by the a auctioneer node with request
00008 #     join_auction / close_auction
00009 
00010 # The node will need to run a general server service, that will redirect to the
00011 # correct service callback action according to the received request 
00012 # (e.g. seller node request the auctioneer service sending start_auction 
00013 # message and the node will provide the auctioneer service; 
00014 # auctioneer node request the buyer service sending join_auction message 
00015 # and the node will provide the buyer service 
00016 
00017 
00018 # configuring PYTHONPATH (By default, this will add the src and lib directory for each of your dependencies to your PYTHONPATH)
00019 import roslib; roslib.load_manifest('k-sap_pkg')
00020 
00021 # imports to access Master_API
00022 import os, xmlrpclib
00023 
00024 # import client library
00025 import rospy
00026 
00027 # import messages
00028 import auction_msgs.msg
00029 
00030 # import services
00031 import auction_srvs.srv
00032 
00033 # import services functions
00034 import auctioneer
00035 import buyer_k_sap
00036 
00037 # import auxiliar libraries
00038 import random
00039 import math
00040 
00041 # "global" variables (to be referred as global under def fun(something))
00042 role_assigned = False
00043 actual_role = 'none'
00044 master_server = ''
00045 buyer_server = ''
00046 auctioneer_server = ''
00047 auctioneer_bid_reception_server = ''
00048 
00049 
00050 ############################################################################
00051 ## Auctioneer Services
00052 ############################################################################
00053 def auctioneer_services():
00054 
00055     global auctioneer_server, auctioneer_bid_reception_server
00056 
00057     # create Auctioneer Service
00058     service_path = rospy.get_name()+"/auctioneer_server"
00059 
00060     auctioneer_server = rospy.Service(service_path,
00061                                           auction_srvs.srv.AuctioneerService,
00062                                           auctioneer.handle_auctioneer_server_callback)
00063 
00064     # create Auctioneer Bid Reception Service
00065     service_path = rospy.get_name()+"/auctioneer_bid_reception_server"
00066 
00067     auctioneer_bid_reception_server = rospy.Service(service_path,
00068                                                     auction_srvs.srv.AuctioneerBidReceptionService,
00069                                                     auctioneer.handle_auctioneer_bid_reception_server_callback)
00070 
00071 ## End create_auctioneer_services
00072 
00073 
00074 
00075 ############################################################################
00076 ## Buyer Services
00077 ############################################################################
00078 def buyer_services():
00079 
00080     global buyer_server
00081 
00082     # create Buyer Service
00083     service_path = rospy.get_name()+"/buyer_server"
00084 
00085     buyer_server = rospy.Service(service_path,
00086                                  auction_srvs.srv.BuyerService,
00087                                  buyer_k_sap.handle_buyer_server_callback)
00088 
00089 ## End create_buyer_services
00090 
00091 
00092 
00093 ############################################################################
00094 ## Cleanup Services
00095 ############################################################################
00096 def cleanup():
00097 
00098     global master_server, auctioneer_server, auctioneer_bid_reception_server, buyer_server, role_assigned, actual_role
00099 
00100     print "Cleanup time..."
00101 
00102 
00103     if actual_role == 'auctioneer':
00104 
00105         role_assigned = False
00106         actual_role = 'none'
00107 
00108         """
00109         print "auctioneer services will now shutdown"
00110         auctioneer_server.shutdown()
00111         #service_code, service_status, service_uri = master_server.lookupService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_server')
00112         #print 'Service: code:'+str(service_code) + ' status:' + service_status + ' uri:' + service_uri
00113         #master_server.unregisterService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_server',service_uri)
00114         
00115         auctioneer_bid_reception_server.shutdown()
00116         #service_code, service_status, service_uri = master_server.lookupService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_bid_reception_server')
00117         #print 'Service: code:'+str(service_code) + ' status:' + service_status + ' uri:' + service_uri
00118         #master_server.unregisterService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_bid_reception_server',service_uri)
00119         print "auctioneer services shutdown succeeded"
00120         """
00121     elif actual_role == 'buyer':
00122 
00123         role_assigned = False
00124         actual_role = 'none'
00125         """
00126         print "buyer services shutdown succeeded"
00127         buyer_server.shutdown()
00128         #service_code, service_status, service_uri = master_server.lookupService(rospy.get_name(),str(rospy.get_name())+'/buyer_server')
00129         #print 'Service: code:'+str(service_code) + ' status:' + service_status + ' uri:' + service_uri
00130         #master_server.unregisterService(rospy.get_name(),str(rospy.get_name())+'/buyer_server',service_uri)
00131         print "buyer services shutdown succeeded"
00132         """
00133     else:
00134         return "Something wrong happened in cleanup, actual_role invalid to clean..."
00135 ## End cleanup
00136 
00137 
00138 ############################################################################
00139 ## Auction Config Service Callback
00140 ############################################################################
00141 def handle_auction_config_server_callback(auction_req):
00142 
00143     global role_assigned, actual_role
00144     global master_server, buyer_server
00145 
00146 
00147     #master_server = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00148     #print master_server.getSystemState(rospy.get_name())
00149 
00150 
00151     # update number of messages in parameter server
00152     if rospy.has_param('/num_messages'):
00153         num_messages = rospy.get_param('/num_messages')
00154         num_messages += 2
00155         rospy.set_param('/num_messages', num_messages)
00156 
00157 
00158 
00159     #   print '\n\n\n\t\t'
00160     #   print auction_req._connection_header
00161 
00162     # instanciate a ServiceManager (to help cleanup registered services)
00163     #service_manager = rospy.service.ServiceManager()
00164     
00165     # Clean up
00166     if rospy.has_param('/auction_closed'):
00167         if rospy.get_param('/auction_closed') == True:
00168             role_assigned = False
00169     #if auction_req.role == 'none':
00170     #    cleanup()
00171     #    rospy.loginfo(rospy.get_name()+' cleanup')
00172     #    return {'response_info': rospy.get_name()+' cleanup'}
00173 
00174             
00175 
00176     rospy.loginfo(rospy.get_name()+' '+str(role_assigned))
00177 
00178     # avoid node to take another role
00179     if not role_assigned:
00180         role_assigned = True
00181 
00182         if auction_req.role == 'be_auctioneer':
00183             actual_role = 'auctioneer'
00184             auctioneer_services()
00185             return {'response_info':'Auctioneer: '+rospy.get_name()+' ready for auction'}
00186         
00187         elif auction_req.role == 'be_buyer':
00188             actual_role = 'buyer'
00189             buyer_services()
00190             return {'response_info':'Buyer: '+rospy.get_name()+' ready for auction'}
00191         else:
00192             return {'response_info':'invalid role requested'}
00193 
00194 
00195         #if rospy.has_param('/auction_closed'):
00196         #    rospy.set_param('/auction_closed', False)
00197     else:
00198         return {'response_info':'node already have a role'}
00199 
00200 ## End handle_auction_config_server_callback 
00201            
00202 
00203 ############################################################################
00204 ## Main function
00205 ############################################################################
00206 if __name__ == "__main__":
00207         
00208     # initialize node (we will have several nodes, anonymous=True)
00209     rospy.init_node('node', anonymous=True)
00210     
00211     # create the auction_config_server
00212     service_path = rospy.get_name()+"/auction_config_server"
00213 
00214     auction_config_server = rospy.Service(service_path,
00215                                           auction_srvs.srv.AuctionConfigService,
00216                                           handle_auction_config_server_callback)
00217 
00218     # ok, ready to participate
00219     #rospy.loginfo(rospy.get_name()+" is ready to participate in the auction.")
00220     
00221     # Prevent node from exit until shutdown
00222     rospy.spin()
00223 
00224 ## End main


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