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('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_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     #if rospy.has_param('/auction_close'):
00058     #    if rospy.get_param('/auction_close') == True:
00059     #        auctioneer_server.shutdown('auction_closing')
00060     #        auctioneer_bid_reception_server.shutdown('auction_closing')
00061 
00062     # create Auctioneer Service
00063     service_path = rospy.get_name()+"/auctioneer_server"
00064 
00065     auctioneer_server = rospy.Service(service_path, auction_srvs.srv.AuctioneerService, auctioneer.handle_auctioneer_server_callback)
00066     
00067 
00068     # create Auctioneer Bid Reception Service
00069     service_path = rospy.get_name()+"/auctioneer_bid_reception_server"
00070 
00071     auctioneer_bid_reception_server = rospy.Service(service_path, auction_srvs.srv.AuctioneerBidReceptionService, auctioneer.handle_auctioneer_bid_reception_server_callback)
00072 
00073 
00074     #if rospy.has_param('/auction_close'):
00075     #    if rospy.get_param('/auction_close') == True:
00076     #        auctioneer_server.shutdown('auction_closing')
00077     #        auctioneer_bid_reception_server.shutdown('auction_closing')
00078     
00079 ## End create_auctioneer_services
00080 
00081 
00082 
00083 ############################################################################
00084 ## Buyer Services
00085 ############################################################################
00086 def buyer_services():
00087 
00088     global buyer_server
00089 
00090     # service_manager = rospy.service.ServiceManager()
00091 
00092     #if rospy.has_param('/auction_close'):
00093     #    if rospy.get_param('/auction_closed') == True:
00094     #        buyer_server.shutdown('auction_closing')
00095 
00096     #        print "\nDoes the code enter here???\n"
00097             
00098 
00099     # create Buyer Service
00100     service_path = rospy.get_name()+"/buyer_server"
00101     
00102     buyer_server = rospy.Service(service_path, auction_srvs.srv.BuyerService, buyer_sap.handle_buyer_server_callback)
00103 
00104     #buyer_server.spin()
00105     # if rospy.has_param('/auction_close'):
00106     #    if rospy.get_param('/auction_closed') == True:
00107     #        buyer_server.shutdown('auction_closing')
00108 
00109     
00110 ## End create_buyer_services
00111 
00112 
00113 ############################################################################
00114 ## Cleanup Services
00115 ############################################################################
00116 def cleanup():
00117 
00118     global master_server, auctioneer_server, auctioneer_bid_reception_server, buyer_server, role_assigned, actual_role
00119 
00120     print "Cleanup time..."
00121 
00122 
00123     if actual_role == 'auctioneer':
00124 
00125         role_assigned = False
00126         actual_role = 'none'
00127 
00128         """
00129         print "auctioneer services will now shutdown"
00130         auctioneer_server.shutdown()
00131         #service_code, service_status, service_uri = master_server.lookupService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_server')
00132         #print 'Service: code:'+str(service_code) + ' status:' + service_status + ' uri:' + service_uri
00133         #master_server.unregisterService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_server',service_uri)
00134         
00135         auctioneer_bid_reception_server.shutdown()
00136         #service_code, service_status, service_uri = master_server.lookupService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_bid_reception_server')
00137         #print 'Service: code:'+str(service_code) + ' status:' + service_status + ' uri:' + service_uri
00138         #master_server.unregisterService(rospy.get_name(),str(rospy.get_name())+'/auctioneer_bid_reception_server',service_uri)
00139         print "auctioneer services shutdown succeeded"
00140         """
00141     elif actual_role == 'buyer':
00142 
00143         role_assigned = False
00144         actual_role = 'none'
00145         """
00146         print "buyer services shutdown succeeded"
00147         buyer_server.shutdown()
00148         #service_code, service_status, service_uri = master_server.lookupService(rospy.get_name(),str(rospy.get_name())+'/buyer_server')
00149         #print 'Service: code:'+str(service_code) + ' status:' + service_status + ' uri:' + service_uri
00150         #master_server.unregisterService(rospy.get_name(),str(rospy.get_name())+'/buyer_server',service_uri)
00151         print "buyer services shutdown succeeded"
00152         """
00153     else:
00154         return "Something wrong happened in cleanup, actual_role invalid to clean..."
00155 ## End cleanup
00156 
00157 
00158 
00159 ############################################################################
00160 ## Auction Config Service Callback
00161 ############################################################################
00162 def handle_auction_config_server_callback(auction_req):
00163 
00164     global role_assigned, actual_role
00165     global master_server, buyer_server
00166 
00167 
00168     #master_server = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00169     #print master_server.getSystemState(rospy.get_name())
00170 
00171 
00172     # update number of messages in parameter server
00173     if rospy.has_param('/num_messages'):
00174         num_messages = rospy.get_param('/num_messages')
00175         num_messages += 2
00176         rospy.set_param('/num_messages', num_messages)
00177 
00178 
00179 
00180     #   print '\n\n\n\t\t'
00181     #   print auction_req._connection_header
00182 
00183     # instanciate a ServiceManager (to help cleanup registered services)
00184     #service_manager = rospy.service.ServiceManager()
00185     
00186     # Clean up
00187     if rospy.has_param('/auction_closed'):
00188         if rospy.get_param('/auction_closed') == True:
00189             role_assigned = False
00190     #if auction_req.role == 'none':
00191     #    cleanup()
00192     #    rospy.loginfo(rospy.get_name()+' cleanup')
00193     #    return {'response_info': rospy.get_name()+' cleanup'}
00194 
00195             
00196 
00197     rospy.loginfo(rospy.get_name()+' '+str(role_assigned))
00198 
00199     # avoid node to take another role
00200     if not role_assigned:
00201         role_assigned = True
00202 
00203         if auction_req.role == 'be_auctioneer':
00204             actual_role = 'auctioneer'
00205             auctioneer_services()
00206             return {'response_info':'Auctioneer: '+rospy.get_name()+' ready for auction'}
00207         
00208         elif auction_req.role == 'be_buyer':
00209             actual_role = 'buyer'
00210             buyer_services()
00211             return {'response_info':'Buyer: '+rospy.get_name()+' ready for auction'}
00212         else:
00213             return {'response_info':'invalid role requested'}
00214 
00215 
00216         #if rospy.has_param('/auction_closed'):
00217         #    rospy.set_param('/auction_closed', False)
00218     else:
00219         return {'response_info':'node already have a role'}
00220 
00221 ## End handle_auction_config_server_callback            
00222 
00223 
00224 
00225 ############################################################################
00226 ## Main function
00227 ############################################################################
00228 if __name__ == "__main__":
00229         
00230     # initialize node (we will have several nodes, anonymous=True)
00231     rospy.init_node('node', anonymous=True)
00232     
00233     # create the auction_config_server
00234     service_path = rospy.get_name()+"/auction_config_server"
00235 
00236     auction_config_server = rospy.Service(service_path,
00237                                           auction_srvs.srv.AuctionConfigService,
00238                                           handle_auction_config_server_callback) 
00239     
00240     # ok, ready to participate
00241     # rospy.loginfo(rospy.get_name()+" is ready to participate in the auction.")
00242 
00243     # Prevent node from exit until node shutdown
00244     rospy.spin()
00245 
00246 ## End main


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