wifi_signal_pub.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 import struct
4 import os
5 from rtabmap_ros.msg import UserData
6 
7 def loop():
8  rospy.init_node('wifi_signal_pub', anonymous=True)
9  pub = rospy.Publisher('wifi_signal', UserData, queue_size=10)
10  rate = rospy.Rate(0.5) # 0.5hz
11  while not rospy.is_shutdown():
12 
13  myCmd = os.popen('nmcli dev wifi | grep "^*"').read()
14  cmdList = myCmd.split()
15 
16  if len(cmdList) > 6:
17  quality = float(cmdList[6])
18  msg = UserData()
19 
20  # To make it compatible with c++ sub example, use dBm
21  dBm = quality/2-100
22  rospy.loginfo("Network \"%s\": Quality=%d, %f dBm", cmdList[1], quality, dBm)
23 
24  # Create user data [level, stamp].
25  # Any format is accepted.
26  # However, if CV_8UC1 format is used, make sure rows > 1 as
27  # rtabmap will think it is already compressed.
28  msg.rows = 1
29  msg.cols = 2
30  msg.type = 6 # Use OpenCV type (here 6=CV_64FC1): http://ninghang.blogspot.com/2012/11/list-of-mat-type-in-opencv.html
31 
32  # We should set stamp in data to be able to
33  # retrieve it from the saved user data as we need
34  # to get precise position in the graph afterward.
35  msg.data = struct.pack(b'dd', dBm, rospy.get_time())
36 
37  pub.publish(msg)
38  else:
39  rospy.logerr("Cannot get info from wireless!")
40  rate.sleep()
41 
42 if __name__ == '__main__':
43  try:
44  loop()
45  except rospy.ROSInterruptException:
46  pass


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19