Go to the documentation of this file.00001 
00002 import roslib
00003 roslib.load_manifest('mini_maxwell')
00004 import rospy
00005 import sys
00006 import random
00007 import os
00008 
00009 import rospkg
00010 rospack = rospkg.RosPack()
00011 sys.path.append(rospack.get_path('mini_maxwell') + "/scripts")
00012 
00013 from mm2client import *
00014 from dynamic_reconfigure.server import Server as DynamicReconfigureServer
00015 from mini_maxwell.cfg import RosClientConfig as ConfigType
00016 
00017 class MMRondomConnection():
00018     def __init__(self):
00019         MM_REV = 12
00020         if MM_REV >= 12:
00021         
00022             try:
00023                 self.bnds = GetCurrentBands(mm2name)
00024             except:
00025                 self.bnds = Bands()
00026         else: 
00027             self.bnds = Bands()
00028 
00029         
00030         self.mm2name = rospy.get_param('~ip', '192.168.0.5')
00031         self.round_trip  = rospy.get_param('~round_trip', 500) 
00032         self.rate_limit = rospy.get_param('~rate_limit', 100000000) 
00033         self.connection_A = True
00034         self.connection_B = True
00035         self.band_number = 5
00036 
00037         rospy.loginfo('mm2 hostname or ip = %s', self.mm2name)
00038 
00039         
00040         self.server = DynamicReconfigureServer(ConfigType, self.reconfigure)
00041         rospy.Timer(rospy.Duration(1), self.changeConnection)
00042         rospy.spin()
00043 
00044     def reconfigure(self, config, level):
00045         self.round_trip = config["round_trip"]
00046         self.rate_limit = config["rate_limit"]
00047 
00048         
00049         self.updateMM()
00050         return config
00051 
00052     def changeConnection(self, event):
00053         present_connection_A = self.connection_A
00054         present_connection_B = self.connection_B
00055 
00056         if random.randint(0, 1):
00057             self.connection_A = True
00058             rospy.loginfo('A: Connected')
00059         else:
00060             self.connection_A = False
00061             rospy.loginfo('A: Not connected')
00062 
00063         if random.randint(0, 1):
00064             self.connection_B = True
00065             rospy.loginfo('B: Connected')
00066         else:
00067             self.connection_B = False
00068             rospy.loginfo('B: Not connected')
00069         
00070         
00071         self.updateMM()
00072 
00073     def updateMM(self):
00074         self.bnds.SetDelayAmount(self.band_number, True, self.round_trip)
00075         self.bnds.SetDelayAmount(self.band_number, False, self.round_trip)
00076         if self.connection_A:
00077             rate_limit_A = self.rate_limit
00078         else:
00079             rate_limit_A = 128 
00080 
00081         if self.connection_B:
00082             rate_limit_B = self.rate_limit
00083         else:
00084             rate_limit_B = 128 
00085 
00086         self.bnds.SetRateLimit(self.band_number, True, rate_limit_A)
00087         self.bnds.SetRateLimit(self.band_number, False, rate_limit_B)
00088         self.bnds.SetDelayReorder(self.band_number, True, False)
00089         self.bnds.SetDelayReorder(self.band_number, False, False)
00090 
00091         rospy.loginfo('round_trip = %s', self.round_trip)
00092         rospy.loginfo('rate_limit_A = %s', rate_limit_A)
00093         rospy.loginfo('rate_limit_B = %s', rate_limit_B)
00094         
00095         ChangeBandsOnMM(self.bnds, self.mm2name)
00096 
00097 
00098 if __name__ == '__main__':
00099     rospy.init_node('mini_maxwell_rondom_connection')
00100 
00101     try:
00102         mmc = MMRondomConnection()
00103     except rospy.ROSInterruptException: pass