documentation and clean up

This commit is contained in:
Florian Zirker 2018-12-16 17:35:47 +01:00
parent 692d1e83f9
commit 2ec1d70e97
4 changed files with 106 additions and 125 deletions

View file

@ -8,20 +8,19 @@ AllowAllParametersOfDeclarationOnNextLine: false
AllowShortIfStatementsOnASingleLine: false AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false AllowShortLoopsOnASingleLine: false
AllowShortFunctionsOnASingleLine: None AllowShortFunctionsOnASingleLine: None
AllowShortLoopsOnASingleLine: false
AlwaysBreakTemplateDeclarations: true AlwaysBreakTemplateDeclarations: true
AlwaysBreakBeforeMultilineStrings: false AlwaysBreakBeforeMultilineStrings: false
BreakBeforeBinaryOperators: false BreakBeforeBinaryOperators: false
BreakBeforeTernaryOperators: false BreakBeforeTernaryOperators: false
BreakConstructorInitializersBeforeComma: true BreakConstructorInitializersBeforeComma: true
BinPackParameters: true BinPackParameters: false
ColumnLimit: 120 ColumnLimit: 100
ConstructorInitializerAllOnOneLineOrOnePerLine: true ConstructorInitializerAllOnOneLineOrOnePerLine: true
DerivePointerBinding: false DerivePointerBinding: false
PointerBindsToType: true PointerBindsToType: true
ExperimentalAutoDetectBinPacking: false ExperimentalAutoDetectBinPacking: false
IndentCaseLabels: true IndentCaseLabels: true
MaxEmptyLinesToKeep: 1 MaxEmptyLinesToKeep: 2
NamespaceIndentation: None NamespaceIndentation: None
ObjCSpaceBeforeProtocolList: true ObjCSpaceBeforeProtocolList: true
PenaltyBreakBeforeFirstCallParameter: 19 PenaltyBreakBeforeFirstCallParameter: 19
@ -46,6 +45,7 @@ SpaceBeforeAssignmentOperators: true
ContinuationIndentWidth: 4 ContinuationIndentWidth: 4
SortIncludes: false SortIncludes: false
SpaceAfterCStyleCast: false SpaceAfterCStyleCast: false
AlignConsecutiveAssignments: true
# Configure each individual brace in BraceWrapping # Configure each individual brace in BraceWrapping
BreakBeforeBraces: Custom BreakBeforeBraces: Custom

View file

@ -1,42 +1,32 @@
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 2.8.3)
project(wlan_pioneer) project(wlan_pioneer)
add_compile_options(-std=c++11)
find_package(catkin REQUIRED COMPONENTS find_package(catkin REQUIRED COMPONENTS
roscpp roscpp
std_msgs std_msgs
message_generation message_generation
) )
add_message_files( add_message_files(FILES WlanSignalMsg.msg)
FILES
WlanSignalMsg.msg
)
generate_messages( generate_messages(DEPENDENCIES std_msgs)
DEPENDENCIES
std_msgs
)
catkin_package() catkin_package()
include_directories( include_directories(${catkin_INCLUDE_DIRS} /usr/local/include/)
${catkin_INCLUDE_DIRS} link_directories(${catkin_INCLUDE_DIRS} /usr/local/lib/)
/usr/local/include/
)
link_directories(
${catkin_INCLUDE_DIRS}
/usr/local/lib/
)
add_executable(wlanSignal src/wlanSignal.cpp) add_executable(wlanSignal src/wlanSignal.cpp)
target_link_libraries(wlanSignal ${catkin_LIBRARIES} wifi-scan) target_link_libraries(wlanSignal ${catkin_LIBRARIES} wifi-scan)
add_dependencies(wlanSignal wlan_pioneer_generate_messages_cpp) add_dependencies(wlanSignal wlan_pioneer_generate_messages_cpp)
SET(CMAKE_INSTALL_RPATH ${catkin_LIBRARIES}) # This setting disable new dtags for ld linker. So RUNPATH is
SET(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) # 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") SET(CMAKE_EXE_LINKER_FLAGS "-Wl,--disable-new-dtags")

View file

@ -1,7 +1,7 @@
<launch> <launch>
<!-- <param name="wlan_interface" type="string" value="wlx74da38ef8aca" /> --> <param name="wlan_interface" type="string" value="wlx74da38ef8aca" />
<!-- <param name="wlan_ssid" type="string" value="HSMA-VPN" /> --> <param name="wlan_ssid" type="string" value="HSMA-VPN" />
<node pkg="wlan_pioneer" type="wlanSignal" name="wlanSignal" launch-prefix="sudo -S -E"/> <node pkg="wlan_pioneer" type="wlanSignal" name="wlanSignal" launch-prefix="sudo -S -E"/>

View file

@ -1,60 +1,60 @@
#include "ros/ros.h"
#include "wlan_pioneer/WlanSignalMsg.h"
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
#include <cstring> #include <cstring>
#include <limits> #include <limits>
#include <string>
#include "ros/ros.h"
#include "wlan_pioneer/WlanSignalMsg.h"
#include "wifi_scan.h" #include "wifi_scan.h"
using namespace std; using namespace std;
using namespace ros; using namespace ros;
using namespace wlan_pioneer; 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 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 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 ) { 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_2G4 = numeric_limits<int8_t>::min();
msg.level_5G = numeric_limits<int8_t>::min(); msg.level_5G = numeric_limits<int8_t>::min();
msg.cellCount_2G4 = 0; msg.cellCount_2G4 = 0;
msg.cellCount_5G = 0; msg.cellCount_5G = 0;
if ( wifi == nullptr ) { if ( wifi == nullptr ) {
// initialise wlan for scanning
wifi = wifi_scan_init( interface.c_str() ); wifi = wifi_scan_init( interface.c_str() );
} }
int status = wifi_scan_all( wifi, bss, MAX_APS ); int status = wifi_scan_all( wifi, bss, MAX_APS );
if ( status < 0 ) { if ( status < 0 ) {
ROS_ERROR( "Unable to get WLAN scan data: %s", std::strerror( errno ) ); 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; wifi = nullptr;
return; return;
} }
else { else {
// run trought list of cells
for ( int i = 0; i < status && i < MAX_APS; ++i ) { for ( int i = 0; i < status && i < MAX_APS; ++i ) {
if ( bss[i].seen_ms_ago > 100 ) { if ( bss[i].seen_ms_ago > 100 ) {
continue; // we do not want old results continue; // we do not want old results
} }
if ( std::strcmp( bss[i].ssid, monitoringSsid.c_str() ) != 0 ) { 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 ) { 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.level_2G4 = std::max( msg.level_2G4, level );
msg.cellCount_2G4++; msg.cellCount_2G4++;
} }
else if ( bss[i].frequency >= 5000 && bss[i].frequency <= 5999 ) { 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.level_5G = std::max( msg.level_5G, level );
msg.cellCount_5G++; msg.cellCount_5G++;
} }
@ -62,12 +62,15 @@ void scanInterface( const string& interface, const string& monitoringSsid ) {
} }
} }
int main( int argc, char** argv ) { int main( int argc, char** argv ) {
init( argc, argv, "wlanSignal" ); init( argc, argv, "wlanSignal" );
NodeHandle node; NodeHandle node;
string wlanInterface; string wlanInterface;
string monitoringSsid; string monitoringSsid;
Publisher publisher = node.advertise<WlanSignalMsg>( "wlan_signal", 1000 );
Rate loopRate = Rate( 1 ); // every second
if ( node.param<string>( "wlan_ssid", monitoringSsid, "" ) ) { if ( node.param<string>( "wlan_ssid", monitoringSsid, "" ) ) {
ROS_INFO( "Param wlan_ssid: %s", monitoringSsid.c_str() ); 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'" ); 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() ) { while ( ok() ) {
scanInterface( wlanInterface, monitoringSsid ); scanInterface( wlanInterface, monitoringSsid );
msg.timestamp = Time::now(); ROS_INFO( "Signal strength 2.4G: %i (%d Cells) Signal strength 5G: %i "
"(%d Cells)",
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 );
msg.level_2G4,
msg.cellCount_2G4,
msg.level_5G,
msg.cellCount_5G);
publisher.publish( msg ); publisher.publish( msg );
spinOnce(); spinOnce();
loopRate.sleep(); loopRate.sleep();