Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
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
00039 ros::init(argc, argv, "fingerprint");
00040 ros::NodeHandle node;
00041 ros::Rate rate(1);
00042
00043
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
00051 std::vector<int> channels;
00052 channels.push_back(1);
00053 channels.push_back(6);
00054 channels.push_back(11);
00055
00056
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