read wlan signal with command line tool iwconfig
This commit is contained in:
parent
10cc704de3
commit
f64bfae42d
1 changed files with 33 additions and 4 deletions
|
@ -1,25 +1,54 @@
|
||||||
#include "ros/ros.h"
|
#include "ros/ros.h"
|
||||||
#include "wlan_pioneer/WlanSignalMsg.h"
|
#include "wlan_pioneer/WlanSignalMsg.h"
|
||||||
#include <sstream>
|
#include <iostream>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
using namespace ros;
|
using namespace ros;
|
||||||
using namespace wlan_pioneer;
|
using namespace wlan_pioneer;
|
||||||
|
|
||||||
|
string GetStdoutFromCommand(const string &cmd)
|
||||||
|
{
|
||||||
|
string data;
|
||||||
|
FILE *stream;
|
||||||
|
const int max_buffer = 256;
|
||||||
|
char buffer[max_buffer];
|
||||||
|
//cmd.append(" 2>&1");
|
||||||
|
|
||||||
|
stream = popen(cmd.c_str(), "r");
|
||||||
|
if (stream)
|
||||||
|
{
|
||||||
|
while (!feof(stream))
|
||||||
|
{
|
||||||
|
if (fgets(buffer, max_buffer, stream) != NULL)
|
||||||
|
{
|
||||||
|
data.append(buffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
pclose(stream);
|
||||||
|
}
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
int main(int argc, char **argv)
|
||||||
{
|
{
|
||||||
|
// TODO: make interface configurable
|
||||||
|
string singalLevelCmd("iwconfig wlp3s0 | grep Signal | cut -d \"=\" -f3 | cut -d \" \" -f1");
|
||||||
|
|
||||||
init(argc, argv, "wlanSignal");
|
init(argc, argv, "wlanSignal");
|
||||||
NodeHandle node;
|
NodeHandle node;
|
||||||
|
|
||||||
// topic: wlan_signal
|
// topic: wlan_signal
|
||||||
Publisher publisher = node.advertise<WlanSignalMsg>("wlan_signal", 1000);
|
Publisher publisher = node.advertise<WlanSignalMsg>("wlan_signal", 1000);
|
||||||
|
|
||||||
Rate loopRate(1); // every second
|
Rate loopRate(1); // every second
|
||||||
|
|
||||||
while (ros::ok())
|
while (ros::ok())
|
||||||
{
|
{
|
||||||
WlanSignalMsg msg;
|
WlanSignalMsg msg;
|
||||||
msg.timestamp = ros::Time::now();
|
msg.timestamp = ros::Time::now();
|
||||||
msg.level_24G = 0; // TODO: read real WLAN signal strength
|
msg.level_24G = stol(GetStdoutFromCommand(singalLevelCmd));
|
||||||
msg.level_5G = 0;
|
msg.level_5G = 0;
|
||||||
|
|
||||||
ROS_INFO("Signal strength 2.4G: %li Signal strength 5G: %li", msg.level_24G, msg.level_5G);
|
ROS_INFO("Signal strength 2.4G: %li Signal strength 5G: %li", msg.level_24G, msg.level_5G);
|
||||||
|
|
Loading…
Reference in a new issue