43 from diagnostic_msgs.msg
import DiagnosticStatus, KeyValue, DiagnosticArray
44 from jsk_network_tools.msg
import WifiStatus
48 extracted = re.match(
'^[0-9.-]*', s).group()
52 return float(extracted)
62 output = subprocess.check_output([
"iwconfig", self.
dev],
63 stderr=subprocess.STDOUT)
64 except subprocess.CalledProcessError
as e:
65 rospy.logdebug(
"iwconfig command return non-zero code: %s" % str(e.returncode))
67 for entity
in re.split(
'\s{2,}', output.replace(
'=',
':').replace(
'"',
'')):
68 splitted = entity.split(
':')
69 if len(splitted) >= 2:
70 key = entity.split(
':')[0].strip()
71 value =
":".join(entity.split(
':')[1:]).strip()
73 q1, q2 = value.split(
'/')
74 value = str(float(q1) / float(q2))
77 if "ESSID" not in self.
status:
84 elif "off" in self.
status[
"ESSID"]:
91 self.
ifname = rospy.get_param(
"~network_interface",
"wlan0")
92 self.
rate = rospy.get_param(
"~update_rate", 1.0)
95 self.
status_pub = rospy.Publisher(
"~status", WifiStatus, queue_size=1)
96 self.
diagnostic_pub = rospy.Publisher(
"/diagnostics", DiagnosticArray, queue_size=1)
98 def poll(self, event=None):
105 msg.header.stamp = rospy.Time.now()
106 msg.interface = self.
ifname 107 msg.enabled = self.iwconfig.is_enabled()
108 msg.connected = self.iwconfig.is_connected()
109 if self.iwconfig.is_connected():
110 msg.ssid = self.iwconfig.status[
"ESSID"]
112 msg.access_point = self.iwconfig.status[
"Access Point"]
115 msg.link_quality =
extract_number(self.iwconfig.status[
"Link Quality"])
116 msg.signal_level =
extract_number(self.iwconfig.status[
"Signal level"])
117 self.status_pub.publish(msg)
118 except Exception
as e:
119 rospy.logerr(
"Failed to publish status: %s" % str(e))
120 rospy.logerr(traceback.format_exc())
123 da = DiagnosticArray()
124 ds = DiagnosticStatus()
125 ds.name = rospy.get_caller_id().lstrip(
'/') +
': Status' 126 ds.hardware_id = self.
ifname 127 if not self.iwconfig.is_enabled():
128 ds.level = DiagnosticStatus.STALE
129 ds.message =
"Device not found" 130 elif not self.iwconfig.is_connected():
131 ds.level = DiagnosticStatus.ERROR
132 ds.message =
"No connection" 135 ds.level = DiagnosticStatus.WARN
136 ds.message =
"Connected, but bad quality" 138 ds.level = DiagnosticStatus.OK
139 ds.message =
"Connected" 140 for key, val
in self.iwconfig.status.items():
141 ds.values.append(KeyValue(key, val))
143 da.header.stamp = rospy.Time.now()
144 self.diagnostic_pub.publish(da)
145 except Exception
as e:
146 rospy.logerr(
'Failed to publish diagnostic: %s' % str(e))
147 rospy.logerr(traceback.format_exc())
149 if __name__ ==
'__main__':
150 rospy.init_node(
"network_status")
def poll(self, event=None)
def publish_diagnostic(self)