wifi_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 import roslib; roslib.load_manifest('kingfisher_bringup')
00004 
00005 import rospy
00006 from std_msgs.msg import Bool
00007 import subprocess
00008 
00009 
00010 rospy.init_node('wifi_monitor')
00011 
00012 pub = rospy.Publisher('has_wifi', Bool)
00013 dev = rospy.get_param('~dev', 'wlan0')
00014 hz = rospy.get_param('~hz', 1)
00015 previous_error = False
00016 previous_success = False
00017 r = None
00018 
00019 while not rospy.is_shutdown():
00020   try:
00021     wifi_str = subprocess.check_output(['ifconfig', dev], stderr=subprocess.STDOUT);
00022     if "inet addr" in wifi_str:
00023       pub.publish(True)
00024     else:
00025       pub.publish(False)
00026 
00027     if not previous_success:
00028       previous_success = True
00029       previous_error = False
00030       rospy.loginfo("Retrieved status of interface %s. Now updating at %f Hz." % (dev, hz))
00031       r = rospy.Rate(hz)
00032 
00033   except subprocess.CalledProcessError:
00034     if not previous_error:
00035       previous_error = True
00036       previous_success = False
00037       rospy.logerr("Error checking status of interface %s. Will try again every 10s." % dev)
00038       r = rospy.Rate(0.1)
00039     
00040   r.sleep()


kingfisher_node
Author(s): Mike Purvis
autogenerated on Sat Dec 28 2013 17:08:10