ll_com.c
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           RT-WMP              --------------------
00003  *------------------------------------------------------------------------
00004  *                                                         V7.0B  11/05/10
00005  *
00006  *
00007  *  File: ./src/platforms/linux_us/hwi/ath5k/ll_com.c
00008  *  Authors: Samuel Cabrero, Danilo Tardioli
00009  *  ----------------------------------------------------------------------
00010  *  Copyright (C) 2000-2010, Universidad de Zaragoza, SPAIN
00011  *
00012  *  Contact Addresses: Danilo Tardioli                   dantard@unizar.es
00013  *
00014  *  RT-WMP is free software; you can  redistribute it and/or  modify it
00015  *  under the terms of the GNU General Public License  as published by the
00016  *  Free Software Foundation;  either  version 2, or (at  your option) any
00017  *  later version.
00018  *
00019  *  RT-WMP  is distributed  in the  hope  that  it will be   useful, but
00020  *  WITHOUT  ANY  WARRANTY;     without  even the   implied   warranty  of
00021  *  MERCHANTABILITY  or  FITNESS FOR A  PARTICULAR PURPOSE.    See the GNU
00022  *  General Public License for more details.
00023  *
00024  *  You should have received  a  copy of  the  GNU General Public  License
00025  *  distributed with RT-WMP;  see file COPYING.   If not,  write to the
00026  *  Free Software  Foundation,  59 Temple Place  -  Suite 330,  Boston, MA
00027  *  02111-1307, USA.
00028  *
00029  *  As a  special exception, if you  link this  unit  with other  files to
00030  *  produce an   executable,   this unit  does  not  by  itself cause  the
00031  *  resulting executable to be covered by the  GNU General Public License.
00032  *  This exception does  not however invalidate  any other reasons why the
00033  *  executable file might be covered by the GNU Public License.
00034  *
00035  *----------------------------------------------------------------------*/
00036 
00037 #include <sys/types.h>
00038 #include <sys/time.h>
00039 #include <sys/socket.h>
00040 #include <arpa/inet.h>
00041 #include <unistd.h>
00042 
00043 #include <stdlib.h>
00044 #include <stdio.h>
00045 #include <string.h>
00046 #include "errno.h"
00047 #include <pthread.h>
00048 #include "config/compiler.h"
00049 #include "core/include/definitions.h"
00050 #include "core/interface/wmp_interface.h"
00051 #include "core/include/wmp_misc.h"
00052 #include "core/include/ml_com.h"
00053 
00054 
00055 #include <assert.h>
00056 #include <linux/if.h>
00057 #include <linux/if_packet.h>
00058 #include <linux/if_ether.h>
00059 #include <sys/ioctl.h>
00060 #include <linux/if_ether.h>
00061 #include "module/ath5k_interface.h"
00062 
00063 #define WMP_PROTO 0x6969 /* TODO: Mover a un sitio apropiado */
00064 
00065 /* Interface default configuration */
00066 #define DEFAULT_FREQ            5200
00067 #define DEFAULT_RATE            RATE_6M
00068 #define DEFAULT_TXPOWER_DBM 15
00069 #define DEFAULT_ANTENNA_MODE AR5K_ANTMODE_DEFAULT
00070 
00071 #define ATH5K_RATE_CODE_1M      0x1B
00072 #define ATH5K_RATE_CODE_2M      0x1A
00073 #define ATH5K_RATE_CODE_5_5M    0x19
00074 #define ATH5K_RATE_CODE_11M     0x18
00075 /* A and G */
00076 #define ATH5K_RATE_CODE_6M      0x0B
00077 #define ATH5K_RATE_CODE_9M      0x0F
00078 #define ATH5K_RATE_CODE_12M     0x0A
00079 #define ATH5K_RATE_CODE_18M     0x0E
00080 #define ATH5K_RATE_CODE_24M     0x09
00081 #define ATH5K_RATE_CODE_36M     0x0D
00082 #define ATH5K_RATE_CODE_48M     0x08
00083 #define ATH5K_RATE_CODE_54M     0x0C
00084 
00085 static double ath5k_rate[] = { 0, 0, 0, 0, 0, 0, 0, 0, 48, 24, 12, 6, 54, 36,
00086                 18, 9, 0, 0, 0, 0, 0, 0, 0, 0, 11, 5.5, 2, 1, 0, 0, 0, 0, 0 };
00087 
00088 static int rx, tx; /* TX and RX sockets*/
00089 static char dev[20];
00090 static char param[256], val[256];
00091 
00092 static short freq;
00093 static short rate;
00094 static unsigned char txpower_dbm;
00095 static int antenna_mode;
00096 static unsigned short raw_filter = WMP_PROTO;
00097 static struct timeval tv;
00098 
00099 /* Cached frame used for tx */
00100 static unsigned char ethernet_frame[2500];
00101 
00102 void* bridge(void *);
00103 int iw_enum_devices(char  a[10][256]);
00104 int iw_has_module(char * mod);
00105 
00106 void print_packet_hex(char *msg, unsigned char *packet, int len) {
00107         unsigned char *p = packet;
00108 
00109         fprintf(stderr,"---------Packet---Starts----\n");
00110         printf("%s", msg);
00111         while (len--) {
00112                 fprintf(stderr,"%.2x ", *p);
00113                 p++;
00114         }
00115         fprintf(stderr,"\n--------Packet---Ends-----\n\n");
00116 }
00117 
00118 int readllcfg() {
00119         FILE * f;
00120         char filename[256], line[256];
00121         /* Set default values */
00122         sprintf(dev, "wlan0");
00123         freq = DEFAULT_FREQ;
00124         rate = DEFAULT_RATE;
00125         txpower_dbm = DEFAULT_TXPOWER_DBM;
00126         antenna_mode = DEFAULT_ANTENNA_MODE;
00127 
00128         snprintf(filename, 256, "%s/.rt-wmp/rt-wmp-us-ath5k.ll", getenv("HOME"));
00129         f = fopen(filename, "r");
00130 
00131         if (f > 0) {
00132                 WMP_MSG(stderr, "Reading Low Level Configuration file (%s)... \n", filename);
00133                 while (fgets(line,256,f) != NULL) {
00134                         if (line[0]<65 || line[0]>90){
00135                                 continue;
00136                         }
00137                         sscanf(line,"%s %s",param,val);
00138                         int exists = 0;
00139                         if (strcmp(param, "DEVICE") == 0){
00140                                 strcpy(dev, val);
00141                                 exists = 1;
00142                         }
00143                         else if (strcmp(param, "FREQ") == 0){
00144                                 freq = atoi(val);
00145                                 exists = 1;
00146                         }
00147                         else if (strcmp(param, "RATE") == 0){
00148                                 rate = atoi(val);
00149                                 exists = 1;
00150                         }
00151                         else if (strcmp(param, "TXPOWER_DBM") == 0){
00152                                 txpower_dbm = atoi(val);
00153                                 exists = 1;
00154                         }
00155                         else if (strcmp(param, "ANTENNA_MODE") == 0) {
00156                                 if (strcmp(val, "AR5K_ANTMODE_DEFAULT") == 0){
00157                                         antenna_mode = AR5K_ANTMODE_DEFAULT;
00158                                         exists = 1;
00159                                 }
00160                                 else if (strcmp(val, "AR5K_ANTMODE_FIXED_A") == 0){
00161                                         antenna_mode = AR5K_ANTMODE_FIXED_A;
00162                                         exists = 1;
00163                                 }
00164                                 else if (strcmp(val, "AR5K_ANTMODE_FIXED_B") == 0){
00165                                         antenna_mode = AR5K_ANTMODE_FIXED_B;
00166                                         exists = 1;
00167                                 }
00168                                 else if (strcmp(val, "AR5K_ANTMODE_SINGLE_AP") == 0){
00169                                         antenna_mode = AR5K_ANTMODE_SINGLE_AP;
00170                                         exists = 1;
00171                                 }
00172                                 else if (strcmp(val, "AR5K_ANTMODE_SECTOR_AP") == 0){
00173                                         antenna_mode = AR5K_ANTMODE_SECTOR_AP;
00174                                         exists = 1;
00175                                 }
00176                                 else if (strcmp(val, "AR5K_ANTMODE_SECTOR_STA") == 0){
00177                                         antenna_mode = AR5K_ANTMODE_SECTOR_STA;
00178                                 }
00179                                 else if (strcmp(val, "AR5K_ANTMODE_DEBUG") == 0){
00180                                         antenna_mode = AR5K_ANTMODE_DEBUG;
00181                                         exists = 1;
00182                                 }
00183                         }
00184                         if (exists) {
00185                                 WMP_MSG(stderr, "READ OPTION: %s = %s\n", param, val);
00186                         }else{
00187                                 WMP_MSG(stderr, "WARNING ::: UKNOWN OPTION %s\n", param, val);
00188                         }
00189                 }
00190                 WMP_MSG(stderr, "Done.\n");
00191 
00192         } else
00193                 WMP_MSG(stderr, "File %s not found, using default values.\n", filename);
00194         return 0;
00195 }
00196 
00197 void closeLowLevelCom() {
00198         close(rx);
00199         close(tx);
00200 }
00201 
00202 int configure_interface(int sock, char *ifname) {
00203         int ret = 0;
00204         struct ifreq ifr;
00205 
00206         strcpy(ifr.ifr_name, ifname);
00207 
00208         /* Configure freq, rate and power*/
00209         struct ath5k_config_info config_info;
00210 
00211         config_info.frequency = freq;
00212         config_info.rate = rate;
00213         config_info.tx_power_dbm = txpower_dbm;
00214         config_info.antenna_mode = antenna_mode;
00215 
00216         ifr.ifr_data = (void *) &config_info;
00217         if ((ioctl(sock, SIO_SET_CONFIG, &ifr)) < 0) {
00218                 perror("Error configuring interface");
00219                 ret--;
00220         }
00221 
00222         /* Set rx filter */
00223         struct ath5k_rxfilter_info rxfilter_info;
00224 
00225         rxfilter_info.broadcast = true;
00226         rxfilter_info.control = false;
00227         rxfilter_info.promisc = true;
00228 
00229         ifr.ifr_data = (void *) &rxfilter_info;
00230         if ((ioctl(sock, SIO_SET_RXFILTER, &ifr)) < 0) {
00231                 perror("Error setting hw rx filter");
00232                 ret--;
00233         }
00234 
00235         /* Select tx rate, disable soft retries and disable ACK waiting for unicast frames */
00236         struct ath5k_txcontrol_info txcontrol_info;
00237 
00238         txcontrol_info.wait_for_ack = false;
00239         txcontrol_info.use_short_preamble = false;
00240         txcontrol_info.count = 1;
00241 
00242         ifr.ifr_data = (void *) &txcontrol_info;
00243         if ((ioctl(sock, SIO_SET_TXCONTROL, &ifr)) < 0) {
00244                 perror("Error setting tx control");
00245                 ret--;
00246         }
00247 
00248         /* Disable ACK unicast frames */
00249         bool disable_ack = true;
00250 
00251         ifr.ifr_data = (void *) &disable_ack;
00252         if ((ioctl(sock, SIO_SET_DISABLEACK, &ifr)) < 0) {
00253                 perror("Error disabling ack");
00254                 ret--;
00255         }
00256         /* Set debug level */
00257         unsigned int debug_level = ATH5K_DEBUG_NONE;
00258 
00259         ifr.ifr_data = (void *) &debug_level;
00260         if ((ioctl(sock, SIO_SET_DEBUG, &ifr)) < 0) {
00261                 perror("Error disabling debug");
00262                 ret--;
00263         }
00264         return ret;
00265 }
00266 
00267 int initLowLevelCom() {
00268         struct sockaddr_ll rx_addr, tx_addr;
00269         struct ifreq ifr;
00270         struct ethhdr *ethernet_header;
00271         int ret = 0;
00272         unsigned char dst_mac[ETH_ALEN] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF };
00273 
00274         sleep(1);
00275 
00276         if (readllcfg() == -1){
00277                 ret--;
00278         }
00279 
00280         llsetupModule(dev);
00281 
00282         WMP_DBG(LL_COM,
00283                         "Using DEV:%s, %d Mhz, (%d * 100) kbps, %d dBm, Ant. mode %d\n",
00284                         dev, freq, rate, txpower_dbm, antenna_mode);
00285 
00286         raw_filter = ETH_P_ALL;
00287         //raw_filter = WMP_PROTO;
00288 
00289 
00290         /* Create raw sockets using WMP_PROTO for the ethertype field */
00291         if ((rx = socket(PF_PACKET, SOCK_RAW, raw_filter)) < 0) {
00292                 perror("Error creating rx socket");
00293                 ret--;
00294         }
00295         if ((tx = socket(PF_PACKET, SOCK_RAW, WMP_PROTO)) < 0) {
00296                 perror("Error creating tx socket");
00297                 ret--;
00298         }
00299 
00300         memset(&ifr, 0, sizeof(struct ifreq));
00301         memset(&rx_addr, 0, sizeof(rx_addr));
00302         memset(&tx_addr, 0, sizeof(tx_addr));
00303 
00304         strncpy((char *) ifr.ifr_name, dev, IFNAMSIZ);
00305 
00306         /* Brinf iface up */
00307         if (ioctl(rx, SIOCGIFFLAGS, &ifr)) {
00308                 perror("ioctl(SIOCSIFFLAGS)");
00309                 ret--;
00310         }
00311         ifr.ifr_flags |= (IFF_UP | IFF_RUNNING);
00312         if (ioctl(rx, SIOCSIFFLAGS, &ifr)) {
00313                 perror("ioctl(SIOCSIFFLAGS)");
00314                 ret--;
00315         }
00316 
00317         /* Get the Interface Index */
00318         if ((ioctl(rx, SIOCGIFINDEX, &ifr)) < 0) {
00319                 perror("Error getting Interface index");
00320                 ret--;
00321         }
00322 
00323         /* Bind the raw sockets to this interface */
00324         rx_addr.sll_family = AF_PACKET;
00325         rx_addr.sll_ifindex = ifr.ifr_ifindex;
00326         rx_addr.sll_protocol = htons(raw_filter);
00327 
00328         tx_addr.sll_family = AF_PACKET;
00329         tx_addr.sll_ifindex = ifr.ifr_ifindex;
00330         tx_addr.sll_protocol = htons(WMP_PROTO);
00331 
00332         if ((bind(rx, (struct sockaddr *) &rx_addr, sizeof(struct sockaddr_ll)))
00333                         < 0) {
00334                 perror("rx bind error");
00335                 ret--;
00336         }
00337 
00338         if ((bind(tx, (struct sockaddr *) &tx_addr, sizeof(struct sockaddr_ll)))
00339                         < 0) {
00340                 perror("tx bind error");
00341                 ret--;
00342         }
00343 
00344         /* Configure interface */
00345         ret -= configure_interface(rx, dev);
00346 
00347         /* Get the interface MAC for building the ethernet header */
00348         if (ioctl(rx, SIOCGIFHWADDR, &ifr) < 0) {
00349                 perror("ioctl(SIOCGIFHWADDR)");
00350                 ret--;
00351         }
00352 
00353         /* Build ethernet header used for tx */
00354         ethernet_header = (struct ethhdr *) ethernet_frame;
00355         memcpy(ethernet_header->h_dest, dst_mac, ETH_ALEN);
00356         memcpy(ethernet_header->h_source, ifr.ifr_hwaddr.sa_data, ETH_ALEN);
00357         ethernet_header->h_proto = htons(WMP_PROTO);
00358 
00359         int val = 1;
00360         setsockopt(tx, SOL_SOCKET, SO_BROADCAST, &val, sizeof(val));
00361 
00362         if (ret == 0) {
00363                 WMP_DBG(LL_COM, "Low level com init ok.\n");
00364                 return 1;
00365         }
00366 
00367         return 0;
00368 }
00369 
00370 int llsend(char * f, int size) {
00371         unsigned char *p;
00372         int nbytes;
00373 
00374         p = ethernet_frame + ETH_HLEN;
00375 
00376         /* Copy data */
00377         memcpy(p, f, size);
00378         p += size;
00379 
00380         if ((nbytes = sendto(tx, ethernet_frame, p - ethernet_frame, 0, 0, 0)) < 0) {
00381                 perror("sendto()");
00382         }
00383 
00384         return nbytes;
00385 }
00386 
00387 rxInfo llreceive(char *f, int timeout) {
00388         int r;
00389         rxInfo ret;
00390         struct ethhdr * eth_hdr = (struct ethhdr *) f;
00391 
00392         if (timeout > 0) {
00393                 fd_set fd_rx;
00394                 tv.tv_sec = 0;
00395                 tv.tv_usec = 1000 * timeout; /* timeout in ms and not us */
00396                 FD_ZERO(&fd_rx);
00397                 FD_SET(rx, &fd_rx);
00398                 fprintf(stderr,"TO >=  =  OK %d \n",timeout);
00399 
00400                 r = select(FD_SETSIZE, &fd_rx, NULL, NULL, &tv);
00401         } else {
00402                 r = 1;
00403         }
00404 
00405         if (r) {
00406                 int nbytes = recvfrom(rx, (unsigned char *) f, MTU, 0, 0, 0);
00407                 char c_rate = (*(f + ETH_HLEN + 1)); /* ath5k form */
00408                 ret.proto = eth_hdr->h_proto;
00409                 fprintf(stderr,"TO >=  =  proto %d \n",ret.proto);
00410                 ret.error = 0;
00411                 ret.rate = ath5k_rate[c_rate];
00412                 ret.has_lq = 0;
00413                 ret.size = nbytes - ETH_HLEN;
00414                 memmove(f, f + ETH_HLEN, nbytes - ETH_HLEN);
00415 
00416 //              /* calculo RSSI */
00417 //              double dbm = f[0] - 95;
00418 //              double drssi = 4500*sqrt(pow(10,dbm/10));
00419 //
00420 //              drssi = 100*f[0]/75;
00421 //
00422 //              if (drssi > 100){
00423 //                      drssi = 100;
00424 //              }
00425 //              /* calculo RSSI */
00426 //
00427 //              f[0] = (char) drssi;
00428 
00429 
00430                 return ret;
00431         } else {
00432                 ret.error = 1;
00433                 return ret;
00434         }
00435 }
00436 
00437 int llconfig(unsigned short freq, enum rates rate, unsigned char power,
00438                 enum ath5k_ant_mode antenna_mode) {
00439         struct ifreq ifr;
00440         int ret = 0;
00441 
00442         strcpy(ifr.ifr_name, dev);
00443 
00444         /* Configure freq, rate and power*/
00445         struct ath5k_config_info config_info;
00446 
00447         config_info.frequency = freq;
00448         config_info.rate = rate;
00449         config_info.tx_power_dbm = power;
00450         config_info.antenna_mode = antenna_mode;
00451 
00452         ifr.ifr_data = (void *) &config_info;
00453         if ((ioctl(rx, SIO_SET_CONFIG, &ifr)) < 0) {
00454                 perror("Error configuring interface");
00455                 ret--;
00456         }
00457 
00458         wmpSetRate((float) rate / 10.0);
00459 
00460         return ret;
00461 }
00462 
00463 
00464 int llsetPower(int f){
00465 
00466 }
00467 
00468 
00469 int llsetupModule(char * devi){
00470         int res = 0;
00471         if (iw_has_module("ath5k ")){
00472                 fprintf(stderr,"Removing module(s)...");
00473                 res = system("rmmod ath5k");
00474                 fprintf(stderr,"Done\n");
00475         }
00476 
00477         if (! iw_has_module("ath5k_raw")){
00478                 char module[256];
00479                 fprintf(stderr,"Installing ath5k_raw...");
00480                 snprintf(module, 256, "insmod %s/.rt-wmp/ath5k_raw.ko", getenv("HOME"));
00481                 res = system(module);
00482                 if (res == -1){
00483                         fprintf(stderr,"*** Unable to install module, exiting\n");
00484                         exit(1);
00485                 }else{
00486                         fprintf(stderr,"Done\n");
00487                 }
00488         }
00489 
00490         fprintf(stderr,"Identifying interface...");
00491         char dev[10][256];
00492         int count = iw_enum_devices(dev), i;
00493 
00494         struct ifreq ifr;
00495         int sock;
00496         if ((sock = socket(PF_PACKET, SOCK_RAW, ETH_P_ALL)) < 0) {
00497                 perror("Error creating socket, exiting...");
00498                 exit(1);
00499         }
00500         int done = 0;
00501         for(i = 0; i< count; i++){
00502                 strcpy(ifr.ifr_name, dev[i]);
00503                 int disable_ack = 1;
00504                 ifr.ifr_data = (void *) &disable_ack;
00505                 if ((ioctl(sock, SIO_SET_DISABLEACK, &ifr)) < 0) {
00506                         continue ;
00507                 }else{
00508                         fprintf(stderr,"%s\n",dev[i]);
00509                         sprintf(devi,"%s",dev[i]);
00510                         done = 1;
00511                         break;
00512                 }
00513         }
00514 
00515         if (!done){
00516                 perror("Unable to found ath5k_raw interface, exiting...\n");
00517                 exit(1);
00518         }
00519         return 1;
00520 }
00521 
00522 /* IW-CODE */
00523 int iw_has_module(char * mod) {
00524         FILE * f = fopen("/proc/modules","r");
00525         char text[2000];
00526         fread(text,2000,1,f);
00527         fclose(f);
00528         return (strstr(text,mod) != 0);
00529 }
00530 
00531 static inline char * iw_get_ifname(char * name, int nsize, char * buf){
00532         char * end;
00533         while (isspace(*buf)){
00534                 buf++;
00535         }
00536         end = strrchr(buf, ':');
00537         if ((end == NULL) || (((end - buf) + 1) > nsize))
00538                 return (NULL);
00539 
00540         memcpy(name, buf, (end - buf));
00541         name[end - buf] = '\0';
00542         return (end);
00543 }
00544 
00545 
00546 int iw_enum_devices(char  a[10][256]) {
00547         char buff[1024];
00548         struct ifconf ifc;
00549         struct ifreq *ifr;
00550         int i, count = 0;
00551 
00552         FILE * fh = fopen("/proc/net/dev", "r");
00553         if (fh != NULL) {
00554                 fgets(buff, sizeof(buff), fh);
00555                 fgets(buff, sizeof(buff), fh);
00556 
00557                 while (fgets(buff, sizeof(buff), fh)) {
00558                         char name[IFNAMSIZ + 1], *s;
00559 
00560                         if ((buff[0] == '\0') || (buff[1] == '\0')){
00561                                 continue;
00562                         }
00563                         s = iw_get_ifname(name, sizeof(name), buff);
00564 
00565                         if (!s) {
00566                                 fprintf(stderr, "Cannot parse /proc/net/dev \n");
00567                         } else {
00568                                 strcpy(a[count],name);
00569                                 count ++;
00570                         }
00571                 }
00572                 fclose(fh);
00573                 return count;
00574         } else {
00575                 return 0;
00576         }
00577 }
00578 
00579 


ros_rt_wmp
Author(s): Danilo Tardioli, dantard@unizar.es
autogenerated on Mon Oct 6 2014 08:27:10