documentation and clean up
This commit is contained in:
parent
692d1e83f9
commit
2ec1d70e97
4 changed files with 106 additions and 125 deletions
|
@ -8,20 +8,19 @@ AllowAllParametersOfDeclarationOnNextLine: false
|
|||
AllowShortIfStatementsOnASingleLine: false
|
||||
AllowShortLoopsOnASingleLine: false
|
||||
AllowShortFunctionsOnASingleLine: None
|
||||
AllowShortLoopsOnASingleLine: false
|
||||
AlwaysBreakTemplateDeclarations: true
|
||||
AlwaysBreakBeforeMultilineStrings: false
|
||||
BreakBeforeBinaryOperators: false
|
||||
BreakBeforeTernaryOperators: false
|
||||
BreakConstructorInitializersBeforeComma: true
|
||||
BinPackParameters: true
|
||||
ColumnLimit: 120
|
||||
BinPackParameters: false
|
||||
ColumnLimit: 100
|
||||
ConstructorInitializerAllOnOneLineOrOnePerLine: true
|
||||
DerivePointerBinding: false
|
||||
PointerBindsToType: true
|
||||
ExperimentalAutoDetectBinPacking: false
|
||||
IndentCaseLabels: true
|
||||
MaxEmptyLinesToKeep: 1
|
||||
MaxEmptyLinesToKeep: 2
|
||||
NamespaceIndentation: None
|
||||
ObjCSpaceBeforeProtocolList: true
|
||||
PenaltyBreakBeforeFirstCallParameter: 19
|
||||
|
@ -46,6 +45,7 @@ SpaceBeforeAssignmentOperators: true
|
|||
ContinuationIndentWidth: 4
|
||||
SortIncludes: false
|
||||
SpaceAfterCStyleCast: false
|
||||
AlignConsecutiveAssignments: true
|
||||
|
||||
# Configure each individual brace in BraceWrapping
|
||||
BreakBeforeBraces: Custom
|
||||
|
|
|
@ -1,42 +1,32 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(wlan_pioneer)
|
||||
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
roscpp
|
||||
std_msgs
|
||||
message_generation
|
||||
)
|
||||
|
||||
add_message_files(
|
||||
FILES
|
||||
WlanSignalMsg.msg
|
||||
)
|
||||
add_message_files(FILES WlanSignalMsg.msg)
|
||||
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
std_msgs
|
||||
)
|
||||
generate_messages(DEPENDENCIES std_msgs)
|
||||
|
||||
catkin_package()
|
||||
|
||||
include_directories(
|
||||
${catkin_INCLUDE_DIRS}
|
||||
/usr/local/include/
|
||||
)
|
||||
|
||||
link_directories(
|
||||
${catkin_INCLUDE_DIRS}
|
||||
/usr/local/lib/
|
||||
)
|
||||
include_directories(${catkin_INCLUDE_DIRS} /usr/local/include/)
|
||||
link_directories(${catkin_INCLUDE_DIRS} /usr/local/lib/)
|
||||
|
||||
add_executable(wlanSignal src/wlanSignal.cpp)
|
||||
target_link_libraries(wlanSignal ${catkin_LIBRARIES} wifi-scan)
|
||||
add_dependencies(wlanSignal wlan_pioneer_generate_messages_cpp)
|
||||
|
||||
|
||||
SET(CMAKE_INSTALL_RPATH ${catkin_LIBRARIES})
|
||||
SET(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)
|
||||
|
||||
# This setting disable new dtags for ld linker. So RUNPATH is
|
||||
# replaced with RPATH in wlanSignal executable. We need RPATH
|
||||
# for finding linked libraries at runtime when executed with
|
||||
# sudo. WLAN scanning needs enhanced privileges. With RUNPATH
|
||||
# linker disables LD_LIBRARY_PATH for security reasons if
|
||||
# setuid/setgid is set. So this is a workaround.
|
||||
# https://gitlab.kitware.com/cmake/community/wikis/doc/cmake/RPATH-handling
|
||||
# https://answers.ros.org/question/165246/launch-node-with-root-permissions/
|
||||
SET(CMAKE_EXE_LINKER_FLAGS "-Wl,--disable-new-dtags")
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
<launch>
|
||||
|
||||
<!-- <param name="wlan_interface" type="string" value="wlx74da38ef8aca" /> -->
|
||||
<!-- <param name="wlan_ssid" type="string" value="HSMA-VPN" /> -->
|
||||
<param name="wlan_interface" type="string" value="wlx74da38ef8aca" />
|
||||
<param name="wlan_ssid" type="string" value="HSMA-VPN" />
|
||||
|
||||
<node pkg="wlan_pioneer" type="wlanSignal" name="wlanSignal" launch-prefix="sudo -S -E"/>
|
||||
|
||||
|
|
|
@ -1,60 +1,60 @@
|
|||
#include "ros/ros.h"
|
||||
#include "wlan_pioneer/WlanSignalMsg.h"
|
||||
#include <iostream>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <cstring>
|
||||
#include <limits>
|
||||
#include <string>
|
||||
#include "ros/ros.h"
|
||||
#include "wlan_pioneer/WlanSignalMsg.h"
|
||||
#include "wifi_scan.h"
|
||||
|
||||
using namespace std;
|
||||
using namespace ros;
|
||||
using namespace wlan_pioneer;
|
||||
|
||||
// Global variables for wifi scanning
|
||||
const int MAX_APS = 64; // the maximum amounts of APs (Access Points) we want to store
|
||||
struct wifi_scan* wifi = nullptr; // this stores all the library information
|
||||
struct bss_info bss[MAX_APS]; // this is where we are going to keep informatoin about APs (Access Points)
|
||||
struct bss_info bss[MAX_APS]; // this is where we are going to keep informatoin about APs
|
||||
WlanSignalMsg msg; // global message, will be set and published in every loop
|
||||
|
||||
WlanSignalMsg msg;
|
||||
|
||||
void scanInterface( const string& interface, const string& monitoringSsid ) {
|
||||
|
||||
msg.ssid = monitoringSsid;
|
||||
msg.timestamp = Time::now();
|
||||
msg.level_2G4 = numeric_limits<int8_t>::min();
|
||||
msg.level_5G = numeric_limits<int8_t>::min();
|
||||
msg.cellCount_2G4 = 0;
|
||||
msg.cellCount_5G = 0;
|
||||
|
||||
if ( wifi == nullptr ) {
|
||||
// initialise wlan for scanning
|
||||
wifi = wifi_scan_init( interface.c_str() );
|
||||
}
|
||||
|
||||
int status = wifi_scan_all( wifi, bss, MAX_APS );
|
||||
|
||||
if ( status < 0 ) {
|
||||
ROS_ERROR( "Unable to get WLAN scan data: %s", std::strerror( errno ) );
|
||||
wifi_scan_close( wifi );
|
||||
wifi_scan_close( wifi ); // close wlan to re-init in next loop
|
||||
wifi = nullptr;
|
||||
return;
|
||||
}
|
||||
else {
|
||||
// run trought list of cells
|
||||
for ( int i = 0; i < status && i < MAX_APS; ++i ) {
|
||||
if ( bss[i].seen_ms_ago > 100 ) {
|
||||
continue; // we do not want old results
|
||||
}
|
||||
|
||||
if ( std::strcmp( bss[i].ssid, monitoringSsid.c_str() ) != 0 ) {
|
||||
continue;
|
||||
continue; // only cells on monitoring SSID should be scanned
|
||||
}
|
||||
|
||||
int8_t level = bss[i].signal_mbm / 100;
|
||||
int8_t level = bss[i].signal_mbm / 100; // mBm to dBm
|
||||
if ( bss[i].frequency >= 2400 && bss[i].frequency <= 2499 ) {
|
||||
// this AP is sending on 2.4 GHz band
|
||||
// maximum of scanned levels of 2.4 GHz band
|
||||
msg.level_2G4 = std::max( msg.level_2G4, level );
|
||||
msg.cellCount_2G4++;
|
||||
}
|
||||
else if ( bss[i].frequency >= 5000 && bss[i].frequency <= 5999 ) {
|
||||
// this AP is sending on 5 GHz band
|
||||
// maximum of scanned levels of 5 GHz band
|
||||
msg.level_5G = std::max( msg.level_5G, level );
|
||||
msg.cellCount_5G++;
|
||||
}
|
||||
|
@ -62,12 +62,15 @@ void scanInterface( const string& interface, const string& monitoringSsid ) {
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
int main( int argc, char** argv ) {
|
||||
init( argc, argv, "wlanSignal" );
|
||||
|
||||
NodeHandle node;
|
||||
string wlanInterface;
|
||||
string monitoringSsid;
|
||||
Publisher publisher = node.advertise<WlanSignalMsg>( "wlan_signal", 1000 );
|
||||
Rate loopRate = Rate( 1 ); // every second
|
||||
|
||||
if ( node.param<string>( "wlan_ssid", monitoringSsid, "" ) ) {
|
||||
ROS_INFO( "Param wlan_ssid: %s", monitoringSsid.c_str() );
|
||||
|
@ -83,23 +86,11 @@ int main( int argc, char** argv ) {
|
|||
ROS_INFO( "Param 'wlan_interface' not set. Using 'wlan0'" );
|
||||
}
|
||||
|
||||
// topic: wlan_signal
|
||||
Publisher publisher = node.advertise<WlanSignalMsg>( "wlan_signal", 1000 );
|
||||
Rate loopRate( 1 ); // every second
|
||||
|
||||
msg.ssid = monitoringSsid;
|
||||
|
||||
while ( ok() ) {
|
||||
|
||||
scanInterface( wlanInterface, monitoringSsid );
|
||||
msg.timestamp = Time::now();
|
||||
|
||||
ROS_INFO( "Signal strength 2.4G: %i (%d Cells) Signal strength 5G: %i (%d Cells)",
|
||||
msg.level_2G4,
|
||||
msg.cellCount_2G4,
|
||||
msg.level_5G,
|
||||
msg.cellCount_5G);
|
||||
|
||||
ROS_INFO( "Signal strength 2.4G: %i (%d Cells) Signal strength 5G: %i "
|
||||
"(%d Cells)",
|
||||
msg.level_2G4, msg.cellCount_2G4, msg.level_5G, msg.cellCount_5G );
|
||||
publisher.publish( msg );
|
||||
spinOnce();
|
||||
loopRate.sleep();
|
||||
|
|
Loading…
Reference in a new issue