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('saap_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_saap
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 ## Auction Config Service Callback
00052 ############################################################################
00053 def handle_auction_server_callback(auction_req):
00054 
00055     global role_assigned, actual_role
00056     global master_server, buyer_server
00057 
00058 
00059     # update number of messages in parameter server
00060     if rospy.has_param('/num_messages'):
00061         num_messages = rospy.get_param('/num_messages')
00062         num_messages += 2
00063         rospy.set_param('/num_messages', num_messages)
00064 
00065     # Clean up
00066     if rospy.has_param('/auction_closed'):
00067         if rospy.get_param('/auction_closed') == True:
00068             role_assigned = False
00069 
00070     rospy.loginfo(rospy.get_name()+' '+str(role_assigned))
00071 
00072     # avoid node to take another role
00073     if not role_assigned:
00074         role_assigned = True
00075 
00076         if auction_req.role == 'be_auctioneer':
00077             return auctioneer.handle_auction_server_callback(auction_req)
00078         
00079         elif auction_req.role == 'be_buyer':
00080             return buyer_saap.handle_auction_server_callback(auction_req)
00081 
00082         else:
00083             return {'response_info':'invalid role requested'}
00084 
00085     else:
00086         return {'response_info':'node already have a role'}
00087 ## End handle_auction_server_callback
00088       
00089 ##################################################################################
00090 ## Auction Service (Server)
00091 ##################################################################################
00092 def auction_server():
00093 
00094     service_path = rospy.get_name()+"/auction_server"
00095 
00096     auctioneer_response = rospy.Service(service_path,
00097                                      auction_srvs.srv.AuctionService,
00098                                      handle_auction_server_callback)
00099 
00100     # ok, ready to participate
00101     #rospy.loginfo(rospy.get_name()+" is ready to participate in the auction.")
00102     
00103     # Prevent node from exit until shutdown
00104     rospy.spin()
00105 ## End Auction Service (Server)
00106                 
00107 
00108 #####################################################################################
00109 ## Main function
00110 #####################################################################################
00111 if __name__ == "__main__":
00112         
00113     # initialize node (we will have several nodes, anonymous=True)
00114     rospy.init_node('node', anonymous=True)
00115     
00116     # put service server into action
00117     auction_server()
00118 ## End main


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