fingerprint.cpp
Go to the documentation of this file.
00001 /*
00002  fingerprint publishes the RSSI of all visible WiFi AP's to wifi_fp.
00003  Copyright (C) 2013  Rafael Berkvens rafael.berkvens@ua.ac.be
00004 
00005  This program is free software: you can redistribute it and/or modify
00006  it under the terms of the GNU General Public License as published by
00007  the Free Software Foundation, either version 3 of the License, or
00008  (at your option) any later version.
00009 
00010  This program is distributed in the hope that it will be useful,
00011  but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013  GNU General Public License for more details.
00014 
00015  You should have received a copy of the GNU General Public License
00016  along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017  */
00018 
00019 #include <string>
00020 
00021 #include <ros/ros.h>
00022 #include <ros/time.h>
00023 #include <ros/console.h>
00024 
00025 #include <iwlib.h>
00026 
00027 #include <wifi_scan/Fingerprint.h>
00028 
00029 #include "wifiscan.h"
00030 
00036 int main(int argc, char **argv)
00037 {
00038   /* Set up ROS, get handle, set desired rate. */
00039   ros::init(argc, argv, "fingerprint");
00040   ros::NodeHandle node;
00041   ros::Rate rate(1);
00042 
00043   /* Get parameters from command line. */
00044   ros::NodeHandle private_node_handle_("~");
00045   std::string topic_name;
00046   private_node_handle_.param<std::string>("topic", topic_name, "wifi_fp");
00047   std::string interface;
00048   private_node_handle_.param<std::string>("interface", interface, "wlan0");
00049 
00050   /* Channels are hard-coded for now. */
00051   std::vector<int> channels;
00052   channels.push_back(1);
00053   channels.push_back(6);
00054   channels.push_back(11);
00055 
00056   /* Create topic, scanning object, and start fingerprinting. */
00057   ros::Publisher pub_fingerprint = node.advertise<wifi_scan::Fingerprint>(
00058       topic_name, 10);
00059   WifiScan wifiscan(channels, interface);
00060   while (node.ok())
00061   {
00062     try
00063     {
00064       wifiscan.createFingerprint(&pub_fingerprint);
00065     }
00066     catch (int exception)
00067     {
00068       switch (exception)
00069       {
00070         case WIFISCAN_ERROR_OPENING_IOCTL_SOCKET:
00071           ROS_ERROR_STREAM("Error in WifiScan::createFingerprint:\n"
00072                            << "  Error opening ioctl socket.");
00073           break;
00074         case WIFISCAN_ERROR_IN_IW_SCAN:
00075           ROS_ERROR_STREAM(
00076               "Error in WifiScan::createFingerprint:\n"
00077               << "  Error in iw_scan(). Might be wrong interface.");
00078           break;
00079         default:
00080           ROS_ERROR_STREAM("Error in WifiScan::createFingerprint:\n"
00081                            << "  Unknown error.");
00082       }
00083     }
00084     ros::spinOnce();
00085     rate.sleep();
00086   }
00087 }
00088 
00089 // kate: indent-mode cstyle; indent-width 2; replace-tabs on; 


wifi_scan
Author(s): Rafael Berkvens
autogenerated on Fri Aug 28 2015 13:41:23