ll_com.c
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           RT-WMP              --------------------
00003  *------------------------------------------------------------------------
00004  *
00005  *
00006  *
00007  *  File: ./src/platforms/linux_ks/hwi/ath5k_raw/ll_com.c
00008  *  Authors: Rubén Durán
00009  *           Danilo Tardioli
00010  *  ----------------------------------------------------------------------
00011  *  Copyright (C) 2000-2011, Universidad de Zaragoza, SPAIN
00012  *
00013  *  Contact Addresses: Danilo Tardioli                   dantard@unizar.es
00014  *
00015  *  RT-WMP is free software; you can  redistribute it and/or  modify it
00016  *  under the terms of the GNU General Public License  as published by the
00017  *  Free Software Foundation;  either  version 2, or (at  your option) any
00018  *  later version.
00019  *
00020  *  RT-WMP  is distributed  in the  hope  that  it will be   useful, but
00021  *  WITHOUT  ANY  WARRANTY;     without  even the   implied   warranty  of
00022  *  MERCHANTABILITY  or  FITNESS FOR A  PARTICULAR PURPOSE.    See the GNU
00023  *  General Public License for more details.
00024  *
00025  *  You should have received  a  copy of  the  GNU General Public  License
00026  *  distributed with RT-WMP;  see file COPYING.   If not,  write to the
00027  *  Free Software  Foundation,  59 Temple Place  -  Suite 330,  Boston, MA
00028  *  02111-1307, USA.
00029  *
00030  *  As a  special exception, if you  link this  unit  with other  files to
00031  *  produce an   executable,   this unit  does  not  by  itself cause  the
00032  *  resulting executable to be covered by the  GNU General Public License.
00033  *  This exception does  not however invalidate  any other reasons why the
00034  *  executable file might be covered by the GNU Public License.
00035  *
00036  *----------------------------------------------------------------------*/
00037 
00038 #include "config/compiler.h"
00039 #include "core/include/definitions.h"
00040 #include "core/interface/wmp_interface.h"
00041 #include "core/include/wmp_misc.h"
00042 #include "core/include/ml_com.h"
00043 
00044 
00045 #include <linux/if.h>
00046 #include <linux/if_packet.h>
00047 #include <linux/if_ether.h>
00048 #include <linux/if_ether.h>
00049 #include "module/ath5k_interface.h"
00050 
00051 #include <linux/netdevice.h>
00052 #include <linux/etherdevice.h>
00053 
00054 #define WMP_PROTO 0x6969 /* TODO: Mover a un sitio apropiado */
00055 
00056 /* Interface default configuration */
00057 #define DEFAULT_FREQ            5200
00058 #define DEFAULT_RATE            RATE_6M
00059 #define DEFAULT_TXPOWER_DBM 15
00060 #define DEFAULT_ANTENNA_MODE AR5K_ANTMODE_DEFAULT
00061 
00062 #define ATH5K_RATE_CODE_1M      0x1B
00063 #define ATH5K_RATE_CODE_2M      0x1A
00064 #define ATH5K_RATE_CODE_5_5M    0x19
00065 #define ATH5K_RATE_CODE_11M     0x18
00066 /* A and G */
00067 #define ATH5K_RATE_CODE_6M      0x0B
00068 #define ATH5K_RATE_CODE_9M      0x0F
00069 #define ATH5K_RATE_CODE_12M     0x0A
00070 #define ATH5K_RATE_CODE_18M     0x0E
00071 #define ATH5K_RATE_CODE_24M     0x09
00072 #define ATH5K_RATE_CODE_36M     0x0D
00073 #define ATH5K_RATE_CODE_48M     0x08
00074 #define ATH5K_RATE_CODE_54M     0x0C
00075 
00076 static double ath5k_rate[] = { 0, 0, 0, 0, 0, 0, 0, 0, 48, 24, 12, 6, 54, 36,
00077       18, 9, 0, 0, 0, 0, 0, 0, 0, 0, 11, 5.5, 2, 1, 0, 0, 0, 0, 0 };
00078 
00079 /* Interface ath5k_raw used for tx and rx */
00080 static struct net_device *interfaz;
00081 
00082 static char param[256], val[256];
00083 
00084 static short freq;
00085 static short rate;
00086 static unsigned char txpower_dbm;
00087 static int antenna_mode;
00088 static int ath5k_if_was_up;
00089 
00090 /* Cached frame used for tx */
00091 static unsigned char ethernet_frame[2500];
00092 
00093 void print_packet_hex(char *msg, unsigned char *packet, int len) {
00094    unsigned char *p = packet;
00095 
00096    printk(KERN_INFO "---------Packet---Starts----\n");
00097    printk(KERN_INFO "%s\n", msg);
00098    while (len--) {
00099       printk(KERN_INFO "%.2x ", *p);
00100       p++;
00101    }
00102    printk(KERN_INFO "\n--------Packet---Ends-----\n\n");
00103 }
00104 
00105 int readllcfg(void) {
00106    struct file *f;
00107    char line[256];
00108    int exists;
00109 
00110 
00111    /* Set default values */
00112    freq = DEFAULT_FREQ;
00113    rate = DEFAULT_RATE;
00114    txpower_dbm = DEFAULT_TXPOWER_DBM;
00115    antenna_mode = DEFAULT_ANTENNA_MODE;
00116 
00117    f = filp_open("/etc/rt-wmp/linux_ks-ath5k.ll", O_RDONLY, 0);
00118 
00119    if (!IS_ERR(f)) {
00120       WMP_MSG(stderr, "Reading Low Level Configuration file (/etc/rt-wmp/linux_ks-ath5k.ll)... \n");
00121       while (fgets(line,256,f) != NULL) {
00122          if (line[0]<65 || line[0]>90){
00123             continue;
00124          }
00125          sscanf(line,"%s %s",param,val);
00126          exists = 0;
00127          /*if (strcmp(param, "DEVICE") == 0){  //Doesn't make sense for linux_ks
00128             strcpy(dev, val);
00129             exists = 1;
00130          }
00131          else*/ if (strcmp(param, "FREQ") == 0){
00132             freq = atoi(val);
00133             exists = 1;
00134          }
00135          else if (strcmp(param, "RATE") == 0){
00136             rate = atoi(val);
00137             exists = 1;
00138          }
00139          else if (strcmp(param, "TXPOWER_DBM") == 0){
00140             txpower_dbm = atoi(val);
00141             exists = 1;
00142          }
00143          else if (strcmp(param, "ANTENNA_MODE") == 0) {
00144             if (strcmp(val, "AR5K_ANTMODE_DEFAULT") == 0){
00145                antenna_mode = AR5K_ANTMODE_DEFAULT;
00146                exists = 1;
00147             }
00148             else if (strcmp(val, "AR5K_ANTMODE_FIXED_A") == 0){
00149                antenna_mode = AR5K_ANTMODE_FIXED_A;
00150                exists = 1;
00151             }
00152             else if (strcmp(val, "AR5K_ANTMODE_FIXED_B") == 0){
00153                antenna_mode = AR5K_ANTMODE_FIXED_B;
00154                exists = 1;
00155             }
00156             else if (strcmp(val, "AR5K_ANTMODE_SINGLE_AP") == 0){
00157                antenna_mode = AR5K_ANTMODE_SINGLE_AP;
00158                exists = 1;
00159             }
00160             else if (strcmp(val, "AR5K_ANTMODE_SECTOR_AP") == 0){
00161                antenna_mode = AR5K_ANTMODE_SECTOR_AP;
00162                exists = 1;
00163             }
00164             else if (strcmp(val, "AR5K_ANTMODE_SECTOR_STA") == 0){
00165                antenna_mode = AR5K_ANTMODE_SECTOR_STA;
00166             }
00167             else if (strcmp(val, "AR5K_ANTMODE_DEBUG") == 0){
00168                antenna_mode = AR5K_ANTMODE_DEBUG;
00169                exists = 1;
00170             }
00171          }
00172          if (exists) {
00173             WMP_MSG(stderr, "READ OPTION: %s = %s\n", param, val);
00174          }else{
00175             WMP_MSG(stderr, "WARNING ::: UKNOWN OPTION %s\n", param);
00176          }
00177       }
00178       WMP_MSG(stderr, "Done.\n");
00179       filp_close(f,0);
00180    }
00181    else
00182       WMP_MSG(stderr, "File /etc/rt-wmp/linux_ks-ath5k.ll not found, using default values.\n");
00183 
00184    return 0;
00185 }
00186 
00187 void closeLowLevelCom(void) {
00188    /* Restore the previous ath5k_raw interface state */
00189    if(!ath5k_if_was_up)
00190       dev_close(interfaz);
00191 }
00192 
00193 int configure_interface(struct net_device *dev) {
00194    union ath5k_ioctl_info ioctl_info;
00195    int ret = 0;
00196 
00197    /* Configure freq, rate and power*/
00198    ioctl_info.config_info.frequency = freq;
00199    ioctl_info.config_info.rate = rate;
00200    ioctl_info.config_info.tx_power_dbm = txpower_dbm;
00201    ioctl_info.config_info.antenna_mode = antenna_mode;
00202    if ((conf_ath5k(dev, &ioctl_info, SIO_SET_CONFIG)) < 0) {
00203       printk(KERN_ERR "Error configuring interface");
00204       ret--;
00205    }
00206 
00207    /* Set rx filter */
00208    ioctl_info.rxfilter_info.broadcast = true;
00209    ioctl_info.rxfilter_info.control = false;
00210    ioctl_info.rxfilter_info.promisc = true;
00211    if ((conf_ath5k(dev, &ioctl_info, SIO_SET_RXFILTER)) < 0) {
00212       printk(KERN_ERR "Error setting hw rx filter");
00213       ret--;
00214    }
00215 
00216    /* Select tx rate, disable soft retries and disable ACK waiting for unicast frames */
00217    ioctl_info.txcontrol_info.wait_for_ack = false;
00218    ioctl_info.txcontrol_info.use_short_preamble = false;
00219    ioctl_info.txcontrol_info.count = 1;
00220    if ((conf_ath5k(dev, &ioctl_info, SIO_SET_TXCONTROL)) < 0) {
00221       printk(KERN_ERR "Error setting tx control");
00222       ret--;
00223    }
00224 
00225    /* Disable ACK unicast frames */
00226    ioctl_info.disable_ack = true;
00227    if ((conf_ath5k(dev, &ioctl_info, SIO_SET_DISABLEACK)) < 0) {
00228       printk(KERN_ERR "Error disabling ack");
00229       ret--;
00230    }
00231 
00232    /* Set debug level */
00233    ioctl_info.debug_level = ATH5K_DEBUG_NONE;
00234    if ((conf_ath5k(dev, &ioctl_info, SIO_SET_DEBUG)) < 0) {
00235       printk(KERN_ERR "Error disabling debug");
00236       ret--;
00237    }
00238 
00239    return ret;
00240 }
00241 
00242 int initLowLevelCom(void) {
00243 
00244    struct ethhdr *ethernet_header;
00245    int ret = 0;
00246    unsigned char dst_mac[ETH_ALEN] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF };
00247 
00248    msleep(1000);
00249 
00250    if (readllcfg() == -1){
00251       ret--;
00252    }
00253 
00254    /* Get ath5k_raw interface to use */
00255    get_ath5k_slave_dev(&interfaz);
00256 
00257    if (!interfaz)
00258    {
00259       printk(KERN_ERR "Unable to get ath5k_raw interface\n");
00260       return 0;
00261    }
00262 
00263    WMP_DBG(LL_COM,
00264          "Using DEV:%s, %d Mhz, (%d * 100) kbps, %d dBm, Ant. mode %d\n",
00265          interfaz->name, freq, rate, txpower_dbm, antenna_mode);
00266 
00267    /* Store the ath5k_raw interface state and bring the interface up */
00268    ath5k_if_was_up = (interfaz->flags & IFF_UP);
00269    dev_open(interfaz);
00270 
00271    /* Configure the interface */
00272    ret -= configure_interface(interfaz);
00273 
00274    /* Build the ethernet header used for tx */
00275    ethernet_header = (struct ethhdr *) ethernet_frame;
00276    memcpy(ethernet_header->h_dest, dst_mac, ETH_ALEN);
00277    memcpy(ethernet_header->h_source, interfaz->dev_addr, ETH_ALEN);
00278    ethernet_header->h_proto = htons(WMP_PROTO);
00279 
00280    if (ret == 0) {
00281       WMP_DBG(LL_COM, "Low level com init ok.\n");
00282       return 1;
00283    }
00284 
00285    return 0;
00286 }
00287 
00288 int llsend(char * f, int size) {
00289 
00290    unsigned char *p;
00291    struct sk_buff *skb;
00292 
00293    /* Paranoid mode on */
00294    if (!(interfaz->flags & IFF_UP))
00295       return -ENETDOWN;
00296 
00297    if (size + ETH_HLEN > interfaz->mtu + interfaz->hard_header_len)
00298       return -EMSGSIZE;
00299 
00300    skb = alloc_skb(size + ETH_HLEN /*+ LL_RESERVED_SPACE(interfaz)*/, GFP_ATOMIC);
00301 
00302    if (skb == NULL)
00303       return -ENOBUFS;
00304 
00305    //skb_reserve(skb, LL_RESERVED_SPACE(interfaz));
00306 
00307    /* Copy the message into the ethernet frame */
00308    p = ethernet_frame + ETH_HLEN;
00309    memcpy(p, f, size);
00310 
00311    /* Copy the ethernet frame into the skb */
00312    memcpy(skb_put(skb, size+ETH_HLEN),ethernet_frame, size+ETH_HLEN);
00313 
00314    skb->protocol = WMP_PROTO;
00315    skb->dev = interfaz;
00316 
00317    /* Send the skb directly through the ath5k_raw interface */
00318 #if LINUX_VERSION_CODE < KERNEL_VERSION(2,6,30)
00319    interfaz->hard_start_xmit(skb, interfaz);
00320 #else
00321    interfaz->netdev_ops->ndo_start_xmit(skb, interfaz);
00322 #endif
00323 
00324    return size;
00325 }
00326 
00327 rxInfo llreceive(char *f, int timeout) {
00328 
00329    struct sk_buff *skb;
00330    rxInfo ret;
00331    char c_rate;
00332    struct ethhdr * eth_hdr = (struct ethhdr *) f;
00333 
00334    memset(&ret, 0, sizeof(ret));
00335 
00336    if (ath5k_rx_timeout(&skb, timeout)) {
00337       skb_push(skb, ETH_HLEN);        /* Recover the ethernet header */
00338 
00339       memcpy(f, skb->data, skb->len);
00340       c_rate = (*(f + ETH_HLEN + 1)); /* ath5k form */
00341       ret.proto = eth_hdr->h_proto;
00342       ret.rate = ath5k_rate[(int) c_rate];
00343       ret.size = skb->len - ETH_HLEN;
00344       memmove(f, f + ETH_HLEN, ret.size); /* Copy the IP packet */
00345 
00346       /* Free the skb */
00347       kfree_skb(skb); //dev_kfree_skb(skb);
00348 
00349       return ret;
00350    } else {
00351       ret.error = 1;
00352       return ret;
00353    }
00354 }


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