base.c
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------------
00002  *-------------------------        ATH5K Driver          -----------------------
00003  *------------------------------------------------------------------------------
00004  *                                                           V1.0  08/02/2010
00005  *
00006  *
00007  *  Feb 2010 - Samuel Cabrero <samuelcabrero@gmail.com>
00008  *              Initial release
00009  *
00010  *  ----------------------------------------------------------------------------
00011  *  Copyright (C) 2000-2010, Universidad de Zaragoza, SPAIN
00012  *
00013  *  Autors:
00014  *              Samuel Cabrero        <samuelcabrero@gmail.com>
00015  *              Danilo Tardioli       <dantard@unizar.es>
00016  *              Jose Luis Villarroel  <jlvilla@unizar.es>
00017  *
00018  *  This is a simplified version of the original ath5k driver. It should work 
00019  *  with all Atheros 5xxx WLAN cards. The 802.11 layer have been removed so it
00020  *  just send and receive frames over the air, as if it were an Ethernet bus
00021  *  interface.
00022  *
00023  *  Please read ath5k_interface.h for instructions.
00024  *
00025  *  This program is distributed under the terms of GPL version 2 and in the 
00026  *  hope that it will be useful, but WITHOUT ANY WARRANTY; without even the 
00027  *  implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  
00028  *  See the GNU General Public License for more details.
00029  *
00030  *----------------------------------------------------------------------------*/
00031 
00032 /*-
00033  * Copyright (c) 2002-2005 Sam Leffler, Errno Consulting
00034  * Copyright (c) 2004-2005 Atheros Communications, Inc.
00035  * Copyright (c) 2006 Devicescape Software, Inc.
00036  * Copyright (c) 2007 Jiri Slaby <jirislaby@gmail.com>
00037  * Copyright (c) 2007 Luis R. Rodriguez <mcgrof@winlab.rutgers.edu>
00038  *
00039  * All rights reserved.
00040  *
00041  * Redistribution and use in source and binary forms, with or without
00042  * modification, are permitted provided that the following conditions
00043  * are met:
00044  * 1. Redistributions of source code must retain the above copyright
00045  *    notice, this list of conditions and the following disclaimer,
00046  *    without modification.
00047  * 2. Redistributions in binary form must reproduce at minimum a disclaimer
00048  *    similar to the "NO WARRANTY" disclaimer below ("Disclaimer") and any
00049  *    redistribution must be conditioned upon including a substantially
00050  *    similar Disclaimer requirement for further binary redistribution.
00051  * 3. Neither the names of the above-listed copyright holders nor the names
00052  *    of any contributors may be used to endorse or promote products derived
00053  *    from this software without specific prior written permission.
00054  *
00055  * Alternatively, this software may be distributed under the terms of the
00056  * GNU General Public License ("GPL") version 2 as published by the Free
00057  * Software Foundation.
00058  *
00059  * NO WARRANTY
00060  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00061  * ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00062  * LIMITED TO, THE IMPLIED WARRANTIES OF NONINFRINGEMENT, MERCHANTIBILITY
00063  * AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
00064  * THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR SPECIAL, EXEMPLARY,
00065  * OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00066  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00067  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
00068  * IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00069  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF
00070  * THE POSSIBILITY OF SUCH DAMAGES.
00071  *
00072  */
00073 
00074 #include <drivers/osdep.h>
00075 #include "ath5k.h"
00076 #include "base.h"
00077 #include "reg.h"
00078 #include "debug.h"
00079 #include "ath5k_interface.h"
00080 
00081 #include "ath5k_linux_layer.h"
00082 #include "mac80211.h"
00083 
00084 static int ath5k_calinterval = 10;
00085 static int modparam_all_channels = true;
00086 
00087 //DANI
00088 static sem_t ws;
00089 
00090 /******************\
00091 * Internal defines *
00092 \******************/
00093 
00094 /* Known PCI ids */
00095 static const struct ath5k_device_ids ath5k_pci_id_table[] = {
00096         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0207, .driver_data = AR5K_AR5210,
00097                 .name = "5210" }, /* 5210 early */
00098         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0007, .driver_data = AR5K_AR5210,
00099                 .name = "5210" }, /* 5210 */
00100         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0011, .driver_data = AR5K_AR5211,
00101                 .name = "5311" }, /* 5311 - this is on AHB bus !*/
00102         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0012, .driver_data = AR5K_AR5211,
00103             .name = "5211" }, /* 5211 */
00104         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0013, .driver_data = AR5K_AR5212,
00105                 .name = "5212" }, /* 5212 */
00106         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0013, .driver_data = AR5K_AR5212,
00107             .name = "3com 5212" }, /* 3com 5212 */
00108         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0013, .driver_data = AR5K_AR5212,
00109                 .name = "3com 5212" }, /* 3com 3CRDAG675 5212 */
00110         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x1014, .driver_data = AR5K_AR5212,
00111             .name = "IBM 5212" }, /* IBM minipci 5212 */
00112         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0014, .driver_data = AR5K_AR5212,
00113                 .name = "5212 compatible" }, /* 5212 combatible */
00114         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0015, .driver_data = AR5K_AR5212,
00115                 .name = "5212 compatible" }, /* 5212 combatible */
00116         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0016, .driver_data = AR5K_AR5212,
00117                 .name = "5212 compatible" }, /* 5212 combatible */
00118         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0017, .driver_data = AR5K_AR5212,
00119                 .name = "5212 compatible" }, /* 5212 combatible */
00120         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0018, .driver_data = AR5K_AR5212,
00121                 .name = "5212 compatible" }, /* 5212 combatible */
00122         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x0019, .driver_data = AR5K_AR5212,
00123                 .name = "5212 compatible" }, /* 5212 combatible */
00124         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x001a, .driver_data = AR5K_AR5212,
00125                 .name = "2413" }, /* 2413 Griffin-lite */
00126         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x001b, .driver_data = AR5K_AR5212,
00127                 .name = "5413" }, /* 5413 Eagle */
00128         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x001c, .driver_data = AR5K_AR5212,
00129                 .name = "PCI-E card" }, /* PCI-E cards */
00130         { .vendor = PCI_VENDOR_ID_ATHEROS, .device = 0x001d, .driver_data = AR5K_AR5212,
00131                 .name = "2417" }, /* 2417 Nala */
00132         { 0 }
00133 };
00134 
00135 /* Known SREVs */
00136 static const struct ath5k_srev_name srev_names[] = {
00137         { "5210",       AR5K_VERSION_MAC,       AR5K_SREV_AR5210 },
00138         { "5311",       AR5K_VERSION_MAC,       AR5K_SREV_AR5311 },
00139         { "5311A",      AR5K_VERSION_MAC,       AR5K_SREV_AR5311A },
00140         { "5311B",      AR5K_VERSION_MAC,       AR5K_SREV_AR5311B },
00141         { "5211",       AR5K_VERSION_MAC,       AR5K_SREV_AR5211 },
00142         { "5212",       AR5K_VERSION_MAC,       AR5K_SREV_AR5212 },
00143         { "5213",       AR5K_VERSION_MAC,       AR5K_SREV_AR5213 },
00144         { "5213A",      AR5K_VERSION_MAC,       AR5K_SREV_AR5213A },
00145         { "2413",       AR5K_VERSION_MAC,       AR5K_SREV_AR2413 },
00146         { "2414",       AR5K_VERSION_MAC,       AR5K_SREV_AR2414 },
00147         { "5424",       AR5K_VERSION_MAC,       AR5K_SREV_AR5424 },
00148         { "5413",       AR5K_VERSION_MAC,       AR5K_SREV_AR5413 },
00149         { "5414",       AR5K_VERSION_MAC,       AR5K_SREV_AR5414 },
00150         { "2415",       AR5K_VERSION_MAC,       AR5K_SREV_AR2415 },
00151         { "5416",       AR5K_VERSION_MAC,       AR5K_SREV_AR5416 },
00152         { "5418",       AR5K_VERSION_MAC,       AR5K_SREV_AR5418 },
00153         { "2425",       AR5K_VERSION_MAC,       AR5K_SREV_AR2425 },
00154         { "2417",       AR5K_VERSION_MAC,       AR5K_SREV_AR2417 },
00155         { "xxxxx",      AR5K_VERSION_MAC,       AR5K_SREV_UNKNOWN },
00156         { "5110",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_5110 },
00157         { "5111",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_5111 },
00158         { "5111A",      AR5K_VERSION_RAD,       AR5K_SREV_RAD_5111A },
00159         { "2111",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_2111 },
00160         { "5112",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_5112 },
00161         { "5112A",      AR5K_VERSION_RAD,       AR5K_SREV_RAD_5112A },
00162         { "5112B",      AR5K_VERSION_RAD,       AR5K_SREV_RAD_5112B },
00163         { "2112",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_2112 },
00164         { "2112A",      AR5K_VERSION_RAD,       AR5K_SREV_RAD_2112A },
00165         { "2112B",      AR5K_VERSION_RAD,       AR5K_SREV_RAD_2112B },
00166         { "2413",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_2413 },
00167         { "5413",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_5413 },
00168         { "2316",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_2316 },
00169         { "2317",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_2317 },
00170         { "5424",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_5424 },
00171         { "5133",       AR5K_VERSION_RAD,       AR5K_SREV_RAD_5133 },
00172         { "xxxxx",      AR5K_VERSION_RAD,       AR5K_SREV_UNKNOWN },
00173 };
00174 
00175 static const struct ieee80211_rate ath5k_rates[] = {
00176         { .bitrate = 10,
00177           .hw_value = ATH5K_RATE_CODE_1M, },
00178         { .bitrate = 20,
00179           .hw_value = ATH5K_RATE_CODE_2M,
00180           .hw_value_short = ATH5K_RATE_CODE_2M | AR5K_SET_SHORT_PREAMBLE,
00181           .flags = IEEE80211_RATE_SHORT_PREAMBLE },
00182         { .bitrate = 55,
00183           .hw_value = ATH5K_RATE_CODE_5_5M,
00184           .hw_value_short = ATH5K_RATE_CODE_5_5M | AR5K_SET_SHORT_PREAMBLE,
00185           .flags = IEEE80211_RATE_SHORT_PREAMBLE },
00186         { .bitrate = 110,
00187           .hw_value = ATH5K_RATE_CODE_11M,
00188           .hw_value_short = ATH5K_RATE_CODE_11M | AR5K_SET_SHORT_PREAMBLE,
00189           .flags = IEEE80211_RATE_SHORT_PREAMBLE },
00190         { .bitrate = 60,
00191           .hw_value = ATH5K_RATE_CODE_6M,
00192           .flags = 0 },
00193         { .bitrate = 90,
00194           .hw_value = ATH5K_RATE_CODE_9M,
00195           .flags = 0 },
00196         { .bitrate = 120,
00197           .hw_value = ATH5K_RATE_CODE_12M,
00198           .flags = 0 },
00199         { .bitrate = 180,
00200           .hw_value = ATH5K_RATE_CODE_18M,
00201           .flags = 0 },
00202         { .bitrate = 240,
00203           .hw_value = ATH5K_RATE_CODE_24M,
00204           .flags = 0 },
00205         { .bitrate = 360,
00206           .hw_value = ATH5K_RATE_CODE_36M,
00207           .flags = 0 },
00208         { .bitrate = 480,
00209           .hw_value = ATH5K_RATE_CODE_48M,
00210           .flags = 0 },
00211         { .bitrate = 540,
00212           .hw_value = ATH5K_RATE_CODE_54M,
00213           .flags = 0 },
00214         /* XR missing */
00215 };
00216 #define ATH5K_NR_RATES   12
00217 
00218 /*
00219  * Prototypes - Internal functions
00220  */
00221 /* Attach detach */
00222 static int ath5k_attach(struct ath5k_softc *sc);
00223 
00224 /* Channel/mode setup */
00225 static inline short ath5k_ieee2mhz(short chan);
00226 static unsigned int ath5k_copy_channels(struct ath5k_hw *ah,
00227                                 struct ieee80211_channel *channels,
00228                                 unsigned int mode,
00229                                 unsigned int max);
00230 static int      ath5k_setup_bands(struct ath5k_softc *sc);
00231 static void     ath5k_mode_setup(struct ath5k_softc *sc);
00232 
00233 /* Descriptor setup */
00234 static int      ath5k_desc_alloc(struct ath5k_softc *sc,
00235                                 struct pci_device *pdev);
00236 
00237 /* Buffers setup */
00238 static int      ath5k_rxbuf_setup(struct ath5k_softc *sc,
00239                                 struct ath5k_buf *bf);
00240 static int      ath5k_txbuf_setup(struct ath5k_softc *sc,
00241                                 struct ath5k_buf *bf);
00242 static inline void ath5k_skb_reset(struct sk_buff *skb)
00243 {
00244         if (!skb)
00245         {
00246                 ATH5K_ERR(sc, "Buffer not allocated.\n");
00247         }
00248         else
00249         {
00250                 skb->len  = 0;
00251                 skb->data = skb->head;
00252                 skb->tail = skb->head;
00253                 memset(skb->head, 0, skb->end - skb->head);
00254         }
00255 }
00256 
00257 /* Queues setup */
00258 static struct ath5k_txq *ath5k_txq_setup(struct ath5k_softc *sc, int qtype, int subtype);
00259 static void                              ath5k_txq_drainq(struct ath5k_softc *sc, struct ath5k_txq *txq);
00260 static void                              ath5k_txq_cleanup(struct ath5k_softc *sc);
00261 
00262 /* Rx handling */
00263 static int      ath5k_rx_start(struct ath5k_softc *sc);
00264 static void ath5k_rx_stop(struct ath5k_softc *sc);
00265 static void ath5k_rx_done(struct ath5k_softc *sc);
00266 
00267 /* Tx handling */
00268 static void ath5k_tx_done(struct ath5k_softc *sc, struct ath5k_txq *txq);
00269 
00270 /* Interrupt handling */
00271 static int ath5k_init(struct ath5k_softc *sc);
00272 static int ath5k_intr(void *dev_id, intr_t irq);
00273 static void ath5k_calibrate(struct ath5k_softc *sc);
00274 
00275 /* Configuration and auxiliary */
00276 static int ath5k_reset(struct ath5k_softc *sc, struct ieee80211_channel *chan);
00277 void ath5k_config_filter (struct ath5k_softc *sc, bool broadcast, bool control, bool promisc);
00278 int ath5k_config_disable_ack (struct ath5k_softc *sc, bool disable);
00279 int ath5k_config(struct ath5k_softc *sc, unsigned short freq, enum rates rate, unsigned char tx_power_dbm,
00280                         enum ath5k_ant_mode antenna_mode);
00281 static struct ieee80211_channel * ath5k_get_channel(struct ath5k_softc *sc, unsigned int freq);
00282 static int ath5k_get_rate_idx(struct ath5k_softc *sc, enum ieee80211_band band, enum rates rate);
00283 static int ath5k_hw_rix_to_bitrate(struct ath5k_softc *sc, int hw_rix);
00284 
00285 /********************\
00286 * PCI Initialization *
00287 \********************/
00288 
00289 static const char *
00290 ath5k_chip_name(enum ath5k_srev_type type, unsigned int val)
00291 {
00292         const char *name = "xxxxx";
00293         unsigned int i;
00294 
00295         for (i = 0; i < ARRAY_SIZE(srev_names); i++) {
00296                 if (srev_names[i].sr_type != type)
00297                         continue;
00298 
00299                 if ((val & 0xf0) == srev_names[i].sr_val)
00300                         name = srev_names[i].sr_name;
00301 
00302                 if ((val & 0xff) == srev_names[i].sr_val) {
00303                         name = srev_names[i].sr_name;
00304                         break;
00305                 }
00306         }
00307 
00308         return name;
00309 }
00310 
00311         struct ath5k_softc *
00312 ath5k_find(const struct ath5k_softc *prev_sc,
00313                 unsigned short freq, enum rates rate, unsigned char tx_power_dbm,
00314                 enum ath5k_ant_mode antenna_mode)
00315 {
00316         struct ath5k_softc *sc;
00317         struct pci_device *pdev, *prev_dev;
00318         void *mem;
00319         int i, ret, rate_idx;
00320         unsigned char csz;
00321 
00322         /* Allocate main driver struct */
00323         sc = (struct ath5k_softc *)malloc(sizeof(struct ath5k_softc));
00324         if (sc == NULL)
00325         {
00326                 ATH5K_ERR(NULL, "Can't allocate main struct.\n");
00327                 return NULL;
00328         }
00329 
00330 
00331         /* Set driver debug level */
00332         ath5k_set_debug_level(sc);
00333 
00334         /* Allocate pci_device structure */
00335         pdev = malloc(sizeof(struct pci_device));
00336         if (pdev == NULL)
00337         {
00338                 ATH5K_ERR(sc, "Can't allocate pci_device struct.\n");
00339                 free(sc);
00340                 return NULL;
00341         }
00342         else
00343                 sc->pdev = pdev;
00344 
00345         /* Find next device in the pci bus */
00346         if (prev_sc != NULL)
00347                 prev_dev = ((struct ath5k_softc *)prev_sc)->pdev;
00348         else
00349                 prev_dev = NULL;
00350 
00351         for (i = 0; i < ARRAY_SIZE(ath5k_pci_id_table); i++)
00352         {
00353                 ret = pci_find_device(ath5k_pci_id_table[i].vendor, ath5k_pci_id_table[i].device, prev_dev, pdev);
00354                 if (ret == 0)
00355                 {
00356                         pdev->name = ath5k_pci_id_table[i].name;
00357                         break;
00358                 }
00359         }
00360         if (ret)
00361         {
00362                 ATH5K_ERR(sc, "Device not found.\n");
00363                 goto err;
00364         }
00365 
00366         /*
00367          * Cache line size is used to size and align various
00368          * structures used to communicate with the hardware.
00369          */
00370         pci_read_config_byte(pdev, PCI_CACHE_LINE_SIZE, &csz);
00371         if (csz == 0)
00372                 ATH5K_WARN(sc, "Cache line size 0.\n");
00373 
00374         /* Set the device as bus master and adjust latency */
00375         adjust_pci_device(pdev);
00376         pci_write_config_byte(pdev, PCI_LATENCY_TIMER, 0xa8);
00377 
00378         /* Get the device base address and IRQ */
00379         mem = (void *)pci_bar_start (pdev, PCI_BASE_ADDRESS_0);
00380         ATH5K_DBG(sc, ATH5K_DEBUG_ANY, "Base memory: %X\n", pdev->membase);
00381         ATH5K_DBG(sc, ATH5K_DEBUG_ANY, "IO Addr: %X\n", pdev->ioaddr);
00382         ATH5K_DBG(sc, ATH5K_DEBUG_ANY, "IRQ: %u\n", pdev->irq);
00383 
00384         /*
00385          * Mark the device as detached to avoid processing
00386          * interrupts until setup is complete.
00387          */
00388         __set_bit(ATH_STAT_INVALID, sc->status);
00389 
00390         sc->iobase = mem;
00391         sc->cachelsz = csz << 2; /* convert to bytes */
00392         /* Setup interrupt handler */
00393         ret = posix_intr_associate(pdev->irq, ath5k_intr, sc, sizeof(struct ath5k_softc)) ||
00394                         posix_intr_unlock(pdev->irq);
00395         if (ret)
00396         {
00397                 ATH5K_ERR(sc, "Can't request IRQ.\n");
00398                 goto err;
00399         }
00400 
00401         /*If we passed the test malloc a ath5k_hw struct*/
00402         sc->ah = (struct ath5k_hw *)malloc(sizeof(struct ath5k_hw));
00403         if (!sc->ah) {
00404                 ret = -ENOMEM;
00405                 ATH5K_ERR(sc, "out of memory\n");
00406                 goto err;
00407         }
00408 
00409         sc->ah->ah_sc = sc;
00410         sc->ah->ah_iobase = sc->iobase;
00411 
00412         /* Initialize device */
00413         ret = ath5k_hw_attach(sc);
00414         if (ret)
00415         {
00416                 ATH5K_ERR(sc, "Error attaching hardware.\n");
00417                 goto err_irq;
00418         }
00419 
00420         /* Finish private driver data initialization */
00421         ret = ath5k_attach(sc);
00422         if (ret)
00423         {
00424                 ATH5K_ERR(sc, "Error initializing.\n");
00425                 goto err_ah;
00426         }
00427 
00428         ATH5K_INFO(sc, "Atheros AR%s chip found (MAC: 0x%x, PHY: 0x%x)\n",
00429                         ath5k_chip_name(AR5K_VERSION_MAC, sc->ah->ah_mac_srev),
00430                                         sc->ah->ah_mac_srev,
00431                                         sc->ah->ah_phy_revision);
00432 
00433         if (!sc->ah->ah_single_chip) {
00434                 /* Single chip radio (!RF5111) */
00435                 if (sc->ah->ah_radio_5ghz_revision &&
00436                         !sc->ah->ah_radio_2ghz_revision) {
00437                         /* No 5GHz support -> report 2GHz radio */
00438                         if (!test_bit(AR5K_MODE_11A,
00439                                 sc->ah->ah_capabilities.cap_mode)) {
00440                                 ATH5K_INFO(sc, "RF%s 2GHz radio found (0x%x)\n",
00441                                         ath5k_chip_name(AR5K_VERSION_RAD,
00442                                                 sc->ah->ah_radio_5ghz_revision),
00443                                                 sc->ah->ah_radio_5ghz_revision);
00444                         /* No 2GHz support (5110 and some
00445                          * 5Ghz only cards) -> report 5Ghz radio */
00446                         } else if (!test_bit(AR5K_MODE_11B,
00447                                 sc->ah->ah_capabilities.cap_mode)) {
00448                                 ATH5K_INFO(sc, "RF%s 5GHz radio found (0x%x)\n",
00449                                         ath5k_chip_name(AR5K_VERSION_RAD,
00450                                                 sc->ah->ah_radio_5ghz_revision),
00451                                                 sc->ah->ah_radio_5ghz_revision);
00452                         /* Multiband radio */
00453                         } else {
00454                                 ATH5K_INFO(sc, "RF%s multiband radio found"
00455                                         " (0x%x)\n",
00456                                         ath5k_chip_name(AR5K_VERSION_RAD,
00457                                                 sc->ah->ah_radio_5ghz_revision),
00458                                                 sc->ah->ah_radio_5ghz_revision);
00459                         }
00460                 }
00461                 /* Multi chip radio (RF5111 - RF2111) ->
00462                  * report both 2GHz/5GHz radios */
00463                 else if (sc->ah->ah_radio_5ghz_revision &&
00464                                 sc->ah->ah_radio_2ghz_revision){
00465                         ATH5K_INFO(sc, "RF%s 5GHz radio found (0x%x)\n",
00466                                 ath5k_chip_name(AR5K_VERSION_RAD,
00467                                         sc->ah->ah_radio_5ghz_revision),
00468                                         sc->ah->ah_radio_5ghz_revision);
00469                         ATH5K_INFO(sc, "RF%s 2GHz radio found (0x%x)\n",
00470                                 ath5k_chip_name(AR5K_VERSION_RAD,
00471                                         sc->ah->ah_radio_2ghz_revision),
00472                                         sc->ah->ah_radio_2ghz_revision);
00473                 }
00474         }
00475 
00476 
00477         /* ready to process interrupts */
00478         __clear_bit(ATH_STAT_INVALID, sc->status);
00479 
00480         /* Set channel pointers */
00481         sc->curchan = ath5k_get_channel(sc, freq);
00482         if (sc->curchan == NULL)
00483         {
00484                 ATH5K_ERR(sc, "Can't set channel %d\n", freq);
00485                 ret = -1;
00486                 goto err_detach;
00487         }
00488         sc->curband = &sc->sbands[sc->curchan->band];
00489 
00490         /* Configurar tx_info */
00491         sc->tx_info.band = sc->curband->band;
00492         rate_idx = ath5k_get_rate_idx(sc, sc->curband->band, rate);
00493         if (rate_idx < 0 || rate_idx > AR5K_MAX_RATES)
00494         {
00495                 ATH5K_ERR(sc, "Can't set rate %d\n", rate);
00496                 ret = -1;
00497                 goto err_detach;
00498         }
00499         sc->tx_info.rate_idx =  rate_idx;
00500         sc->tx_info.count = 1;
00501         sc->tx_info.wait_for_ack = false;
00502         sc->tx_info.use_short_preamble = false;
00503 
00504         /* Configurar filtro */
00505         ath5k_config_filter(sc, true, false, false);
00506 
00507         /* Configurar el envio de ACK en respuesta a tramas unicast */
00508         ret = ath5k_config_disable_ack(sc, false);
00509         if (ret)
00510                 goto err_detach;
00511 
00512         /* Enable interrupts and rx framework */
00513         ret = ath5k_init(sc);
00514         if (ret)
00515                 goto err_detach;
00516 
00517         /* Configurar potencia en pasos de medio dB */
00518         sc->power_level = tx_power_dbm;
00519         ret = ath5k_hw_set_txpower_limit(sc->ah, (sc->power_level * 2));
00520         if (ret)
00521                 goto err_detach;
00522 
00523         /* Configurar modo de antena */
00524         ath5k_hw_set_antenna_mode(sc->ah, antenna_mode);
00525 
00526         /* Resetear despues de configurar la potencia y la antena?
00527          * En principio, de acuerdo con el codigo original no es necesario. */
00528         //ath5k_reset(sc, sc->curchan);
00529 
00530         /* Print initial config */
00531         ATH5K_INFO(sc, "Freq %d Mhz, Rate (%d * 100) kps, Power %d dBm, Ant. mode %d\n",
00532                         sc->curchan->center_freq, rate, sc->power_level, antenna_mode);
00533 
00534         return sc;
00535 err_detach:
00536         /* XXX: Free descriptors and buffers?. Maybe pointless in embedded. */
00537 err_ah:
00538         ath5k_hw_detach(sc->ah);
00539 err_irq:
00540         posix_intr_lock(pdev->irq);
00541         posix_intr_disassociate (pdev->irq, ath5k_intr);
00542 err:
00543         free(pdev);
00544         free(sc);
00545 
00546         return NULL;
00547 }
00548 
00549 
00550 
00551 /***********************\
00552 * Driver Initialization *
00553 \***********************/
00554 
00555 static int
00556 ath5k_attach(struct ath5k_softc *sc)
00557 {
00558         struct pci_device *pdev = sc->pdev;
00559         struct ath5k_hw *ah = sc->ah;
00560         int ret;
00561 
00562         //dani
00563         sem_init(&ws,0,0);
00564 
00565         ATH5K_DBG(sc, ATH5K_DEBUG_ANY, "devid 0x%x\n", pdev->dev_id);
00566 
00567         /*
00568          * Check if the MAC has multi-rate retry support.
00569          * We do this by trying to setup a fake extended
00570          * descriptor.  MAC's that don't have support will
00571          * return false w/o doing anything.  MAC's that do
00572          * support it will return true w/o doing anything.
00573          */
00574         ret = ah->ah_setup_mrr_tx_desc(ah, NULL, 0, 0, 0, 0, 0, 0);
00575         if (ret < 0)
00576                 goto err;
00577         if (ret > 0)
00578                 __set_bit(ATH_STAT_MRRETRY, sc->status);
00579 
00580         /*
00581          * Collect the channel list.  The 802.11 layer
00582          * is resposible for filtering this list based
00583          * on settings like the phy mode and regulatory
00584          * domain restrictions.
00585          */
00586         ret = ath5k_setup_bands(sc);
00587         if (ret) {
00588                 ATH5K_ERR(sc, "can't get channels\n");
00589                 goto err;
00590         }
00591 
00592         /* NB: setup here so ath5k_rate_update is happy */
00593         if (test_bit(AR5K_MODE_11A, ah->ah_modes))
00594                 sc->curband = &sc->sbands[IEEE80211_BAND_5GHZ];
00595         else
00596                 sc->curband = &sc->sbands[IEEE80211_BAND_2GHZ];
00597 
00598         /*
00599          * Allocate tx+rx descriptors and populate the lists.
00600          */
00601         ret = ath5k_desc_alloc(sc, pdev);
00602         if (ret) {
00603                 ATH5K_ERR(sc, "can't allocate descriptors\n");
00604                 goto err;
00605         }
00606 
00607         /*
00608          * Allocate hardware transmit queue. Note that hw functions
00609          * handle reseting these queues at the needed time.
00610          */
00611         sc->txq = ath5k_txq_setup(sc, AR5K_TX_QUEUE_DATA, AR5K_WME_AC_BK);
00612         if (IS_ERR(sc->txq)) {
00613                 ATH5K_ERR(sc, "can't setup xmit queue\n");
00614                 ret = PTR_ERR(sc->txq);
00615                 goto err_desc;
00616         }
00617 
00618         /* Inicializar el anillo de recepcion */
00619         ath5k_ring_init (&sc->rxring);
00620 
00621         sem_init(&sc->tx_sem, 0, 1);
00622 
00623         /* All MAC address bits matter for ACKs */
00624         memset(sc->bssidmask, 0xff, ETH_ALEN);
00625         ath5k_hw_set_bssid_mask(sc->ah, sc->bssidmask);
00626 
00627         return 0;
00628 err_desc:
00629         /* XXX: free descriptors? Maybe pointless in embedded */
00630 err:
00631         return ret;
00632 }
00633 
00634 /********************\
00635 * Channel/mode setup *
00636 \********************/
00637 /* Ugly macro to convert literal channel numbers into their mhz equivalents
00638  * There are certianly some conditions that will break this (like feeding it '30')
00639  * but they shouldn't arise since nothing talks on channel 30. */
00640 #define ieee80211chan2mhz(x) \
00641         (((x) <= 14) ? \
00642         (((x) == 14) ? 2484 : ((x) * 5) + 2407) : \
00643         ((x) + 1000) * 5)
00644 
00645 /*
00646  * Convert IEEE channel number to MHz frequency.
00647  */
00648 static inline short
00649 ath5k_ieee2mhz(short chan)
00650 {
00651         if (chan <= 14 || chan >= 27)
00652                 return ieee80211chan2mhz(chan);
00653         else
00654                 return 2212 + chan * 20;
00655 }
00656 
00657 /*
00658  * Returns true for the channel numbers used without all_channels modparam.
00659  */
00660 static bool ath5k_is_standard_channel(short chan)
00661 {
00662         return ((chan <= 14) ||
00663                 /* UNII 1,2 */
00664                 ((chan & 3) == 0 && chan >= 36 && chan <= 64) ||
00665                 /* midband */
00666                 ((chan & 3) == 0 && chan >= 100 && chan <= 140) ||
00667                 /* UNII-3 */
00668                 ((chan & 3) == 1 && chan >= 149 && chan <= 165));
00669 }
00670 
00671 static unsigned int
00672 ath5k_copy_channels(struct ath5k_hw *ah,
00673                 struct ieee80211_channel *channels,
00674                 unsigned int mode,
00675                 unsigned int max)
00676 {
00677         unsigned int i, count, size, chfreq, freq, ch;
00678 
00679         if (!test_bit(mode, ah->ah_modes))
00680                 return 0;
00681 
00682         switch (mode) {
00683         case AR5K_MODE_11A:
00684         case AR5K_MODE_11A_TURBO:
00685                 /* 1..220, but 2GHz frequencies are filtered by check_channel */
00686                 size = 220 ;
00687                 chfreq = CHANNEL_5GHZ;
00688                 break;
00689         case AR5K_MODE_11B:
00690         case AR5K_MODE_11G:
00691         case AR5K_MODE_11G_TURBO:
00692                 size = 26;
00693                 chfreq = CHANNEL_2GHZ;
00694                 break;
00695         default:
00696                 ATH5K_WARN(ah->ah_sc, "bad mode, not copying channels\n");
00697                 return 0;
00698         }
00699 
00700         for (i = 0, count = 0; i < size && max > 0; i++) {
00701                 ch = i + 1;
00702                 freq = ath5k_ieee2mhz(ch);
00703 
00704                 /* Check if channel is supported by the chipset */
00705                 if (!ath5k_channel_ok(ah, freq, chfreq))
00706                         continue;
00707 
00708                 if (!modparam_all_channels && !ath5k_is_standard_channel(ch))
00709                         continue;
00710 
00711                 /* Write channel info and increment counter */
00712                 channels[count].center_freq = freq;
00713                 channels[count].band = (chfreq == CHANNEL_2GHZ) ?
00714                         IEEE80211_BAND_2GHZ : IEEE80211_BAND_5GHZ;
00715                 switch (mode) {
00716                 case AR5K_MODE_11A:
00717                 case AR5K_MODE_11G:
00718                         channels[count].hw_value = chfreq | CHANNEL_OFDM;
00719                         break;
00720                 case AR5K_MODE_11A_TURBO:
00721                 case AR5K_MODE_11G_TURBO:
00722                         channels[count].hw_value = chfreq |
00723                                 CHANNEL_OFDM | CHANNEL_TURBO;
00724                         break;
00725                 case AR5K_MODE_11B:
00726                         channels[count].hw_value = CHANNEL_B;
00727                 }
00728 
00729                 count++;
00730                 max--;
00731         }
00732 
00733         return count;
00734 }
00735 
00736 static int
00737 ath5k_setup_bands(struct ath5k_softc *sc)
00738 {
00739         struct ath5k_hw *ah = sc->ah;
00740         struct ieee80211_supported_band *sband;
00741         int max_c, count_c = 0;
00742         int i;
00743 
00744         BUILD_BUG_ON(ARRAY_SIZE(sc->sbands) < IEEE80211_NUM_BANDS);
00745         max_c = ARRAY_SIZE(sc->channels);
00746 
00747         /* 2GHz band */
00748         sband = &sc->sbands[IEEE80211_BAND_2GHZ];
00749         sband->band = IEEE80211_BAND_2GHZ;
00750         sband->bitrates = &sc->rates[IEEE80211_BAND_2GHZ][0];
00751 
00752         if (test_bit(AR5K_MODE_11G, sc->ah->ah_capabilities.cap_mode)) {
00753                 /* G mode */
00754                 memcpy(sband->bitrates, &ath5k_rates[0],
00755                        sizeof(struct ieee80211_rate) * 12);
00756                 sband->n_bitrates = 12;
00757 
00758                 sband->channels = sc->channels;
00759                 sband->n_channels = ath5k_copy_channels(ah, sband->channels,
00760                                         AR5K_MODE_11G, max_c);
00761 
00762                 count_c = sband->n_channels;
00763                 max_c -= count_c;
00764         } else if (test_bit(AR5K_MODE_11B, sc->ah->ah_capabilities.cap_mode)) {
00765                 /* B mode */
00766                 memcpy(sband->bitrates, &ath5k_rates[0],
00767                        sizeof(struct ieee80211_rate) * 4);
00768                 sband->n_bitrates = 4;
00769 
00770                 /* 5211 only supports B rates and uses 4bit rate codes
00771                  * (e.g normally we have 0x1B for 1M, but on 5211 we have 0x0B)
00772                  * fix them up here:
00773                  */
00774                 if (ah->ah_version == AR5K_AR5211) {
00775                         for (i = 0; i < 4; i++) {
00776                                 sband->bitrates[i].hw_value =
00777                                         sband->bitrates[i].hw_value & 0xF;
00778                                 sband->bitrates[i].hw_value_short =
00779                                         sband->bitrates[i].hw_value_short & 0xF;
00780                         }
00781                 }
00782 
00783                 sband->channels = sc->channels;
00784                 sband->n_channels = ath5k_copy_channels(ah, sband->channels,
00785                                         AR5K_MODE_11B, max_c);
00786 
00787                 count_c = sband->n_channels;
00788                 max_c -= count_c;
00789         }
00790 
00791         /* 5GHz band, A mode */
00792         if (test_bit(AR5K_MODE_11A, sc->ah->ah_capabilities.cap_mode)) {
00793                 sband = &sc->sbands[IEEE80211_BAND_5GHZ];
00794                 sband->band = IEEE80211_BAND_5GHZ;
00795                 sband->bitrates = &sc->rates[IEEE80211_BAND_5GHZ][0];
00796 
00797                 memcpy(sband->bitrates, &ath5k_rates[4],
00798                        sizeof(struct ieee80211_rate) * 8);
00799                 sband->n_bitrates = 8;
00800 
00801                 sband->channels = &sc->channels[count_c];
00802                 sband->n_channels = ath5k_copy_channels(ah, sband->channels,
00803                                         AR5K_MODE_11A, max_c);
00804 
00805         }
00806 
00807         ath5k_debug_dump_bands(sc);
00808 
00809         return 0;
00810 }
00811 
00812 static void
00813 ath5k_mode_setup(struct ath5k_softc *sc)
00814 {
00815         struct ath5k_hw *ah = sc->ah;
00816         u32 rfilt;
00817 
00818         /* configure rx filter */
00819         rfilt = sc->filter_flags;
00820         ath5k_hw_set_rx_filter(ah, rfilt);
00821 
00822         if (ath5k_hw_hasbssidmask(ah))
00823                 ath5k_hw_set_bssid_mask(ah, sc->bssidmask);
00824 
00825         /* configure operational mode */
00826         ath5k_hw_set_opmode(ah);
00827 
00828         ath5k_hw_set_mcast_filter(ah, 0, 0);
00829         ATH5K_DBG(sc, ATH5K_DEBUG_MODE, "RX filter 0x%x\n", rfilt);
00830 }
00831 
00832 /***************\
00833 * Buffers setup *
00834 \***************/
00835 
00836 static
00837 struct sk_buff *ath5k_rx_skb_alloc(struct ath5k_softc *sc, struct sk_buff *skb)
00838 {
00839         unsigned int off;
00840 
00841         /*
00842          * Allocate buffer with headroom_needed space for the
00843          * fake physical layer header at the start.
00844          */
00845         skb = dev_alloc_skb(sc->rxbufsize + sc->cachelsz - 1);
00846 
00847         if (!skb) {
00848                 ATH5K_ERR(sc, "can't alloc skbuff of size %u\n",
00849                                 sc->rxbufsize + sc->cachelsz - 1);
00850                 return NULL;
00851         }
00852         /*
00853          * Cache-line-align.  This is important (for the
00854          * 5210 at least) as not doing so causes bogus data
00855          * in rx'd frames.
00856          */
00857         off = ((unsigned long)skb->data) % sc->cachelsz;
00858         if (off != 0)
00859                 skb_reserve(skb, sc->cachelsz - off);
00860 
00861         return skb;
00862 }
00863 
00864 static int
00865 ath5k_rxbuf_setup(struct ath5k_softc *sc, struct ath5k_buf *bf)
00866 {
00867         struct ath5k_hw *ah = sc->ah;
00868         struct sk_buff *skb = bf->skb;
00869         struct ath5k_desc *ds;
00870 
00871         /* Reiniciar el skb para recibir una nueva trama */
00872         ath5k_skb_reset(skb);
00873 
00874         /*
00875          * Setup descriptors.  For receive we always terminate
00876          * the descriptor list with a self-linked entry so we'll
00877          * not get overrun under high load (as can happen with a
00878          * 5212 when ANI processing enables PHY error frames).
00879          *
00880          * To insure the last descriptor is self-linked we create
00881          * each descriptor as self-linked and add it to the end.  As
00882          * each additional descriptor is added the previous self-linked
00883          * entry is ``fixed'' naturally.  This should be safe even
00884          * if DMA is happening.  When processing RX interrupts we
00885          * never remove/process the last, self-linked, entry on the
00886          * descriptor list.  This insures the hardware always has
00887          * someplace to write a new frame.
00888          */
00889         ds = bf->desc;
00890         ds->ds_link = (unsigned int)bf->desc;   /* link to self */
00891         ds->ds_data = (unsigned int)skb->data;
00892         ah->ah_setup_rx_desc(ah, ds,
00893                 skb_tailroom(skb),      /* buffer size */
00894                 0);
00895 
00896         if (sc->rxlink != NULL)
00897                 *sc->rxlink = (unsigned int)bf->desc;
00898         sc->rxlink = &ds->ds_link;
00899         return 0;
00900 }
00901 
00902 /*
00903  * Esta funcion rellena el buffer que se le pasa como parametro, lo inserta al
00904  * final de sc->txq y llama al hw.
00905  *
00906  * Contexto: UC
00907  *
00908  * Puede ocurrir:
00909  * - Que la rutina de interrupcion nos expulse, luego hay que bloquear las
00910  *   interrupciones.
00911  */
00912 static int
00913 ath5k_txbuf_setup(struct ath5k_softc *sc, struct ath5k_buf *bf)
00914 {
00915         struct ath5k_hw *ah = sc->ah;
00916         struct ath5k_txq *txq = sc->txq;
00917         struct ath5k_desc *ds = bf->desc;
00918         struct sk_buff *skb = bf->skb;
00919         struct ieee80211_tx_info *info = &sc->tx_info;
00920         unsigned int pktlen, flags, keyidx = AR5K_TXKEYIX_INVALID;
00921         struct ieee80211_rate *rate;
00922         int ret;
00923         u16 hw_rate;
00924         u16 cts_rate = 0;
00925         u16 duration = 0;
00926 
00927         flags = AR5K_TXDESC_INTREQ | AR5K_TXDESC_CLRDMASK;
00928 
00929         if (info->rate_idx >= 0 && info->rate_idx < AR5K_MAX_RATES)
00930                 rate = &sc->sbands[info->band].bitrates[info->rate_idx];
00931         else
00932         {
00933                 ATH5K_ERR(sc, "Rate index invalid\n");
00934                 return -1;
00935         }
00936 
00937         if (!info->wait_for_ack)
00938                 flags |= AR5K_TXDESC_NOACK;
00939 
00940         hw_rate = info->use_short_preamble ? rate->hw_value_short : rate->hw_value;
00941 
00942         pktlen = skb->len;
00943 
00944         /* FIXME: If we are in g mode and rate is a CCK rate
00945          * subtract ah->ah_txpower.txp_cck_ofdm_pwr_delta
00946          * from tx power (value is in dB units already) */
00947         ret = ah->ah_setup_tx_desc(ah, ds, pktlen,
00948                 ath5k_get_hdrlen_from_skb(skb), AR5K_PKT_TYPE_NORMAL,
00949                 (sc->power_level * 2),
00950                 hw_rate,
00951                 info->count, keyidx, ah->ah_tx_ant, flags,
00952                 cts_rate, duration);
00953         if (ret)
00954         {
00955                 ATH5K_ERR(sc, "Error setting up tx descriptor\n");
00956                 return ret;
00957         }
00958 
00959         ds->ds_link = 0;
00960         ds->ds_data = (unsigned int)skb->data;
00961 
00962         cli();
00963         list_add_tail(&bf->list, &txq->q);
00964         if (txq->link == NULL) /* is this first packet? */
00965                 ath5k_hw_set_txdp(ah, txq->qnum, (unsigned int)bf->desc);
00966         else /* no, so only link it */
00967                 *txq->link = (unsigned int)bf->desc;
00968 
00969         txq->link = &ds->ds_link;
00970         ath5k_hw_start_tx_dma(ah, txq->qnum);
00971         sti();
00972 
00973         return 0;
00974 }
00975 
00976 /*******************\
00977 * Descriptors setup *
00978 \*******************/
00979 
00980 static int
00981 ath5k_desc_alloc(struct ath5k_softc *sc, struct pci_device *pdev)
00982 {
00983         struct ath5k_desc *ds;
00984         struct ath5k_buf *bf;
00985         unsigned int i;
00986         int ret;
00987 
00988         /* allocate descriptors */
00989         sc->desc_len = sizeof(struct ath5k_desc) * (ATH_TXBUF + ATH_RXBUF + 1);
00990         sc->desc = (struct ath5k_desc *)malloc(sc->desc_len);
00991         if (sc->desc == NULL) {
00992                 ATH5K_ERR(sc, "can't allocate descriptors\n");
00993                 ret = -ENOMEM;
00994                 goto err;
00995         }
00996         ds = sc->desc;
00997 
00998         bf = calloc(ATH_TXBUF + ATH_RXBUF + 1, sizeof(struct ath5k_buf));
00999         if (bf == NULL) {
01000                 ATH5K_ERR(sc, "can't allocate bufptr\n");
01001                 ret = -ENOMEM;
01002                 goto err_free;
01003         }
01004         sc->bufptr = bf;
01005 
01006         /* Tamaño del buffer de datos de los skb */
01007         sc->rxbufsize = roundup(IEEE80211_MAX_LEN, sc->cachelsz);
01008         ATH5K_DBG(sc, ATH5K_DEBUG_RESET, "cachelsz %u rxbufsize %u\n",
01009                         sc->cachelsz, sc->rxbufsize);
01010 
01011 
01012         INIT_LIST_HEAD(&sc->rxbuf);
01013         for (i = 0; i < ATH_RXBUF; i++, bf++, ds++)
01014         {
01015                 bf->skb  = ath5k_rx_skb_alloc(sc, bf->skb);
01016                 bf->desc = ds;
01017                 list_add_tail(&bf->list, &sc->rxbuf);
01018         }
01019 
01020         INIT_LIST_HEAD(&sc->txbuf);
01021         sc->txbuf_len = ATH_TXBUF;
01022         for (i = 0; i < ATH_TXBUF; i++, bf++, ds++)
01023         {
01024                 bf->skb  = ath5k_rx_skb_alloc(sc, bf->skb);
01025                 bf->desc = ds;
01026                 list_add_tail(&bf->list, &sc->txbuf);
01027         }
01028 
01029         return 0;
01030 err_free:
01031         free(sc->desc);
01032 err:
01033         sc->desc = NULL;
01034         return ret;
01035 }
01036 
01037 
01038 
01039 
01040 /**************\
01041 * Queues setup *
01042 \**************/
01043 
01044 static struct ath5k_txq *
01045 ath5k_txq_setup(struct ath5k_softc *sc,
01046                 int qtype, int subtype)
01047 {
01048         struct ath5k_hw *ah = sc->ah;
01049         struct ath5k_txq *txq;
01050         struct ath5k_txq_info qi = {
01051                 .tqi_subtype = subtype,
01052                 .tqi_aifs = AR5K_TXQ_USEDEFAULT,
01053                 .tqi_cw_min = AR5K_TXQ_USEDEFAULT,
01054                 .tqi_cw_max = AR5K_TXQ_USEDEFAULT
01055         };
01056         int qnum;
01057 
01058         /*
01059          * Enable interrupts only for EOL and DESC conditions.
01060          * We mark tx descriptors to receive a DESC interrupt
01061          * when a tx queue gets deep; otherwise waiting for the
01062          * EOL to reap descriptors.  Note that this is done to
01063          * reduce interrupt load and this only defers reaping
01064          * descriptors, never transmitting frames.  Aside from
01065          * reducing interrupts this also permits more concurrency.
01066          * The only potential downside is if the tx queue backs
01067          * up in which case the top half of the kernel may backup
01068          * due to a lack of tx descriptors.
01069          */
01070         qi.tqi_flags = AR5K_TXQ_FLAG_TXEOLINT_ENABLE |
01071                                 AR5K_TXQ_FLAG_TXDESCINT_ENABLE;
01072         qnum = ath5k_hw_setup_tx_queue(ah, qtype, &qi);
01073         if (qnum < 0) {
01074                 /*
01075                  * NB: don't print a message, this happens
01076                  * normally on parts with too few tx queues
01077                  */
01078                 return ERR_PTR(qnum);
01079         }
01080         if (qnum >= ARRAY_SIZE(sc->txqs)) {
01081                 ATH5K_ERR(sc, "hw qnum %u out of range, max %tu!\n",
01082                         qnum, ARRAY_SIZE(sc->txqs));
01083                 ath5k_hw_release_tx_queue(ah, qnum);
01084                 return ERR_PTR(-EINVAL);
01085         }
01086         txq = &sc->txqs[qnum];
01087         if (!txq->setup) {
01088                 txq->qnum = qnum;
01089                 txq->link = NULL;
01090                 INIT_LIST_HEAD(&txq->q);
01091                 txq->setup = true;
01092         }
01093         return &sc->txqs[qnum];
01094 }
01095 
01096 /* Contexto UC e IRQ en el caso de que la ISR haga un reset
01097  *
01098  * Puede ocurrir:
01099  * - Nos interrumpa una hardIRQ -> cli
01100  * - Nos expulsen de la cpu -> spin_lock
01101  * - Una hardIRQ, softIRQ o UC esta en ejecucion en otra CPU -> spin_lock
01102  */
01103 static void
01104 ath5k_txq_drainq(struct ath5k_softc *sc, struct ath5k_txq *txq)
01105 {
01106         struct ath5k_buf *bf, *bf0;
01107 
01108         /*
01109          * NB: this assumes output has been stopped and
01110          *     we do not need to block ath5k_tx_tasklet
01111          */
01112         cli();
01113         list_for_each_entry_safe(bf, bf0, &txq->q, list) {
01114 
01115                 ath5k_skb_reset(bf->skb);
01116 
01117                 list_move_tail(&bf->list, &sc->txbuf);
01118                 sc->txbuf_len++;
01119         }
01120         txq->link = NULL;
01121         sti();
01122 }
01123 
01124 /*
01125  * Drain the transmit queues and reclaim resources.
01126  */
01127 static void
01128 ath5k_txq_cleanup(struct ath5k_softc *sc)
01129 {
01130         struct ath5k_hw *ah = sc->ah;
01131         unsigned int i;
01132 
01133         /* XXX return value */
01134         if (!test_bit(ATH_STAT_INVALID, sc->status))
01135         {
01136                 /* don't touch the hardware if marked invalid */
01137                 for (i = 0; i < ARRAY_SIZE(sc->txqs); i++)
01138                         if (sc->txqs[i].setup) {
01139                                 ath5k_hw_stop_tx_dma(ah, sc->txqs[i].qnum);
01140                                 ATH5K_DBG(sc, ATH5K_DEBUG_RESET, "txq [%u] %x, link %p\n",
01141                                         sc->txqs[i].qnum,
01142                                         ath5k_hw_get_txdp(ah, sc->txqs[i].qnum),
01143                                         sc->txqs[i].link);
01144                         }
01145         }
01146 
01147         for (i = 0; i < ARRAY_SIZE(sc->txqs); i++)
01148                 if (sc->txqs[i].setup)
01149                         ath5k_txq_drainq(sc, &sc->txqs[i]);
01150 }
01151 
01152 /*************\
01153 * RX Handling *
01154 \*************/
01155 
01156 /*
01157  * Enable the receive h/w following a reset.
01158  *
01159  * Contexto: UC
01160  *
01161  * Bloquear interrupciones.
01162  */
01163 static int
01164 ath5k_rx_start(struct ath5k_softc *sc)
01165 {
01166         struct ath5k_hw *ah = sc->ah;
01167         struct ath5k_buf *bf;
01168         int ret;
01169 
01170         cli();
01171         sc->rxlink = NULL;
01172         list_for_each_entry(bf, &sc->rxbuf, list) {
01173                 ret = ath5k_rxbuf_setup(sc, bf);
01174                 if (ret != 0)
01175                 {
01176                         sti();
01177                         goto err;
01178                 }
01179         }
01180         bf = list_first_entry(&sc->rxbuf, struct ath5k_buf, list);
01181         ath5k_hw_set_rxdp(ah, (unsigned int)bf->desc);
01182         sti();
01183 
01184         ath5k_hw_start_rx_dma(ah);      /* enable recv descriptors */
01185         ath5k_mode_setup(sc);           /* set filters, etc. */
01186         ath5k_hw_start_rx_pcu(ah);      /* re-enable PCU/DMA engine */
01187 
01188         return 0;
01189 err:
01190         return ret;
01191 }
01192 
01193 /*
01194  * Disable the receive h/w in preparation for a reset.
01195  */
01196 static void
01197 ath5k_rx_stop(struct ath5k_softc *sc)
01198 {
01199         struct ath5k_hw *ah = sc->ah;
01200 
01201         ath5k_hw_stop_rx_pcu(ah);       /* disable PCU */
01202         ath5k_hw_set_rx_filter(ah, 0);  /* clear recv filter */
01203         ath5k_hw_stop_rx_dma(ah);       /* disable DMA engine */
01204 
01205         sc->rxlink = NULL;              /* just in case */
01206 }
01207 
01208 static void
01209 ath5k_rx_done(struct ath5k_softc *sc)
01210 {
01211         struct ieee80211_rx_status rxs = {};
01212         struct ath5k_rx_status rs = {};
01213         struct sk_buff *skb;
01214         struct ath5k_buf *bf;
01215         struct ath5k_desc *ds;
01216         int ret;
01217         int hdrlen;
01218         int padsize;
01219         unsigned int sem_value;
01220 
01221 
01222         if (list_empty(&sc->rxbuf)) {
01223                 ATH5K_WARN(sc, "empty rx buf pool\n");
01224                 return;
01225         }
01226         do {
01227                 rxs.flag = 0;
01228 
01229                 bf = list_first_entry(&sc->rxbuf, struct ath5k_buf, list);
01230                 BUG_ON(bf->skb == NULL);
01231                 skb = bf->skb;
01232                 ds = bf->desc;
01233 
01234                 /* bail if HW is still using self-linked descriptor */
01235                 if (ath5k_hw_get_rxdp(sc->ah) == (unsigned int)bf->desc)
01236                         break;
01237 
01238                 ret = sc->ah->ah_proc_rx_desc(sc->ah, ds, &rs);
01239                 if (ret == -EINPROGRESS)
01240                         break;
01241                 else if (ret)
01242                 {
01243                         ATH5K_ERR(sc, "error in processing rx descriptor\n");
01244                         return;
01245                 }
01246 
01247                 if (rs.rs_more)
01248                 {
01249                         ATH5K_WARN(sc, "unsupported jumbo\n");
01250                         goto next;
01251                 }
01252 
01253                 if (rs.rs_status)
01254                 {
01255                         if (rs.rs_status & AR5K_RXERR_PHY)
01256                                 goto next;
01257                         if (rs.rs_status & AR5K_RXERR_CRC)
01258                                 goto next;
01259                         if (rs.rs_status & AR5K_RXERR_DECRYPT)
01260                                 goto next;
01261                         if (rs.rs_status & AR5K_RXERR_MIC) {
01262                                 goto accept;
01263                         }
01264                 }
01265 accept:
01266                 skb_put(skb, rs.rs_datalen);
01267 
01268                 /* The MAC header is padded to have 32-bit boundary if the
01269                  * packet payload is non-zero. The general calculation for
01270                  * padsize would take into account odd header lengths:
01271                  * padsize = (4 - hdrlen % 4) % 4; However, since only
01272                  * even-length headers are used, padding can only be 0 or 2
01273                  * bytes and we can optimize this a bit. In addition, we must
01274                  * not try to remove padding from short control frames that do
01275                  * not have payload. */
01276                 hdrlen = ath5k_get_hdrlen_from_skb(skb);
01277                 padsize = ath5k_pad_size(hdrlen);
01278                 if (padsize) {
01279                         memmove(skb->data + padsize, skb->data, hdrlen);
01280                         skb_pull(skb, padsize);
01281                 }
01282 
01283                 rxs.freq = sc->curchan->center_freq;
01284                 rxs.band = sc->curband->band;
01285 
01286                 rxs.noise = sc->ah->ah_noise_floor;
01287                 rxs.signal = rxs.noise + rs.rs_rssi;
01288 
01289                 /* An rssi of 35 indicates you should be able use
01290                  * 54 Mbps reliably. A more elaborate scheme can be used
01291                  * here but it requires a map of SNR/throughput for each
01292                  * possible mode used */
01293                 rxs.qual = rs.rs_rssi * 100 / 35;
01294 
01295                 /* rssi can be more than 35 though, anything above that
01296                  * should be considered at 100% */
01297                 if (rxs.qual > 100)
01298                         rxs.qual = 100;
01299 
01300                 rxs.antenna = rs.rs_antenna;
01301 
01302                 ath5k_debug_dump_skb(sc, skb, "RX  ", 0);
01303 
01304                 /* skb contains the frame in IEEE 802.11 format, as it was sent over air */
01305                 unsigned char dst[ETH_ALEN];
01306                 unsigned char src[ETH_ALEN];
01307                 unsigned short ethertype, frame_control;
01308                 struct ieee80211_hdr *hdr;
01309                 unsigned char *payload;
01310 
01311                 hdr = (struct ieee80211_hdr *)skb->data;
01312                 frame_control = le16_to_cpu(hdr->frame_control);
01313 
01314                 /* If no payload jump to next frame */
01315                 if (skb->len < 24)
01316                         goto next;
01317 
01318                 /* Extract src/dst addresses */
01319                 switch (frame_control & (IEEE80211_FCTL_FROMDS | IEEE80211_FCTL_TODS)) {
01320                         case IEEE80211_FCTL_FROMDS:
01321                                 memcpy(dst, hdr->addr1, ETH_ALEN);
01322                                 memcpy(src, hdr->addr3, ETH_ALEN);
01323                                 break;
01324                         case IEEE80211_FCTL_TODS:
01325                                 memcpy(dst, hdr->addr3, ETH_ALEN);
01326                                 memcpy(src, hdr->addr2, ETH_ALEN);
01327                                 break;
01328                         case IEEE80211_FCTL_FROMDS | IEEE80211_FCTL_TODS:
01329                                 if (skb->len < IEEE80211_4ADDR_LEN)
01330                                         goto next;
01331                                 memcpy(dst, hdr->addr3, ETH_ALEN);
01332                                 memcpy(src, hdr->addr4, ETH_ALEN);
01333                                 break;
01334                         case 0:
01335                                 memcpy(dst, hdr->addr1, ETH_ALEN);
01336                                 memcpy(src, hdr->addr2, ETH_ALEN);
01337                                 break;
01338                 }
01339 
01340                 payload = skb->data + hdrlen;
01341                 ethertype = (payload[6] << 8) | payload[7];
01342 
01343                 /* convert hdr + possible LLC headers into Ethernet header */
01344                 if (skb->len - hdrlen >= 8)
01345                 {
01346                         /* remove RFC1042 or Bridge-Tunnel encapsulation and
01347                          * replace EtherType */
01348                         skb_pull(skb, hdrlen + SNAP_SIZE);
01349                         memcpy(skb_push(skb, ETH_ALEN), src, ETH_ALEN);
01350                         memcpy(skb_push(skb, ETH_ALEN), dst, ETH_ALEN);
01351                 } else {
01352                         goto next;
01353                 }
01354 
01355                 /* Last 4 bytes are CRC */
01356                 enum rates rate = ath5k_hw_rix_to_bitrate(sc, rs.rs_rate);
01357                 ath5k_ring_insert (&sc->rxring, skb->data, skb->len - 4, rxs.qual, rxs.noise, rate);
01358                 sem_getvalue(&sc->rxring.sem, &sem_value);
01359                 if (sem_value == 0)
01360                         sem_post(&sc->rxring.sem);
01361 
01362 next:
01363                 list_move_tail(&bf->list, &sc->rxbuf);
01364         } while (ath5k_rxbuf_setup(sc, bf) == 0);
01365 }
01366 
01367 
01368 
01369 
01370 /*************\
01371 * TX Handling *
01372 \*************/
01373 
01374 /*
01375  * Contexto IRQ
01376  */
01377 static void
01378 ath5k_tx_done(struct ath5k_softc *sc, struct ath5k_txq *txq)
01379 {
01380         struct ath5k_tx_status ts = {};
01381         struct ath5k_buf *bf, *bf0;
01382         struct ath5k_desc *ds;
01383         struct sk_buff *skb;
01384         int ret;
01385 
01386         list_for_each_entry_safe(bf, bf0, &txq->q, list) {
01387                 ds = bf->desc;
01388 
01389                 ret = sc->ah->ah_proc_tx_desc(sc->ah, ds, &ts);
01390                 if (ret == -EINPROGRESS)
01391                         break;
01392                 else if (ret) {
01393                         ATH5K_ERR(sc, "error %d while processing queue %u\n",
01394                                 ret, txq->qnum);
01395                         break;
01396                 }
01397 
01398                 skb = bf->skb;
01399                 ath5k_skb_reset(skb);
01400 
01401                 if (ts.ts_status)
01402                         sc->ll_stats.dot11ACKFailureCount++;
01403 
01404                 list_move_tail(&bf->list, &sc->txbuf);
01405                 sc->txbuf_len++;
01406         }
01407         if (list_empty(&txq->q))
01408                 txq->link = NULL;
01409 }
01410 
01411 /********************\
01412 * Interrupt handling *
01413 \********************/
01414 
01415 static int
01416 ath5k_init(struct ath5k_softc *sc)
01417 {
01418         struct ath5k_hw *ah = sc->ah;
01419         int ret;
01420 
01421         /*
01422          * The basic interface to setting the hardware in a good
01423          * state is ``reset''.  On return the hardware is known to
01424          * be powered up and with interrupts disabled.  This must
01425          * be followed by initialization of the appropriate bits
01426          * and then setup of the interrupt mask.
01427          */
01428         sc->imask = AR5K_INT_RXOK | AR5K_INT_RXERR | AR5K_INT_RXEOL |
01429                 AR5K_INT_RXORN | AR5K_INT_TXDESC | AR5K_INT_TXEOL |
01430                 AR5K_INT_FATAL | AR5K_INT_GLOBAL | AR5K_INT_SWI;
01431         ret = ath5k_reset(sc, sc->curchan);
01432         if (ret)
01433                 goto done;
01434 
01435         /* Set ack to be sent at low bit-rates */
01436         ath5k_hw_set_ack_bitrate_high(ah, false);
01437 
01438         /* Set PHY calibration inteval */
01439         ah->ah_cal_tstamp.tv_sec = 0;
01440         ah->ah_cal_tstamp.tv_nsec = 0;
01441         ah->ah_cal_intval.tv_sec = ath5k_calinterval;
01442         ah->ah_cal_intval.tv_nsec = 0;
01443 
01444         ret = 0;
01445 done:
01446         return ret;
01447 }
01448 
01449 
01450 static int ath5k_intr(void *data, intr_t irq)
01451 {
01452         struct ath5k_softc *sc = (void*) data;
01453         struct ath5k_hw *ah = sc->ah;
01454         enum ath5k_int status;
01455         unsigned int counter = 1000, rx_intr = 0;
01456 
01457         if (test_bit(ATH_STAT_INVALID, sc->status) ||
01458                                 !ath5k_hw_is_intr_pending(ah))
01459                 return IRQ_NONE;
01460 
01461         do
01462         {
01463                 ath5k_hw_get_isr(ah, &status);          /* NB: clears IRQ too */
01464                 ATH5K_DBG(sc, ATH5K_DEBUG_INTR, "status 0x%x/0x%x\n",
01465                                 status, sc->imask);
01466                 if (status & AR5K_INT_FATAL) {
01467                         /*
01468                          * Fatal errors are unrecoverable.
01469                          * Typically these are caused by DMA errors.
01470                          */
01471                         ATH5K_ERR(sc, "Fatal error (fatal interrupt).\n");
01472                 } else if (unlikely(status & AR5K_INT_RXORN)) {
01473                         ATH5K_ERR(sc, "Fatal error (RX descriptors overrun).\n");
01474                 } else {
01475                         if (status & AR5K_INT_RXEOL) {
01476                                 /*
01477                                 * NB: the hardware should re-read the link when
01478                                 *     RXE bit is written, but it doesn't work at
01479                                 *     least on older hardware revs.
01480                                 */
01481                                 sc->rxlink = NULL;
01482                         }
01483                         if (status & AR5K_INT_TXURN) {
01484                                 /* bump tx trigger level */
01485                                 ath5k_hw_update_tx_triglevel(ah, true);
01486                         }
01487                         if (status & (AR5K_INT_RXOK | AR5K_INT_RXERR)){
01488                                 ath5k_rx_done(sc);
01489                                 rx_intr++;
01490                         }
01491                         if (status & (AR5K_INT_TXOK | AR5K_INT_TXDESC
01492                                         | AR5K_INT_TXERR | AR5K_INT_TXEOL))
01493                                 ath5k_tx_done(sc, sc->txq);
01494 
01495                         if (status & AR5K_INT_SWI)
01496                                 ath5k_calibrate(sc);
01497                         if (status & AR5K_INT_MIB) {
01498                                 /*
01499                                  * These stats are also used for ANI i think
01500                                  * so how about updating them more often ?
01501                                  */
01502                                 ath5k_hw_update_mib_counters(ah, &sc->ll_stats);
01503                         }
01504                 }
01505         } while (ath5k_hw_is_intr_pending(ah) && --counter > 0);
01506 
01507         if (rx_intr == 1){
01508                 sem_post(&ws);
01509 //              fprintf(stderr,"DANI: intr: %d\n", rx_intr);
01510         }
01511 
01512 
01513         if (!counter)
01514                 ATH5K_WARN(sc, "too many interrupts, giving up for now\n");
01515 
01516         ath5k_hw_calibration_poll(ah);
01517 
01518         return IRQ_HANDLED;
01519 }
01520 
01521 
01522 void ath5k_waitFrame(){
01523         sem_wait(&ws);
01524 }
01525 
01526 /*
01527  * Periodically recalibrate the PHY to account
01528  * for temperature/environment changes.
01529  */
01530 static void
01531 ath5k_calibrate(struct ath5k_softc *sc)
01532 {
01533         struct ath5k_hw *ah = sc->ah;
01534 
01535         /* Only full calibration for now */
01536         if (ah->ah_swi_mask != AR5K_SWI_FULL_CALIBRATION)
01537                 return;
01538 
01539         /* Contexto de intr, luego no hay que parar las colas porque nadie
01540          * puede expulsar de la cpu. */
01541 
01542 #if 0
01543         ATH5K_DBG(sc, ATH5K_DEBUG_CALIBRATE, "channel %u/%x\n",
01544                 ath5k_frequency_to_channel(sc->curchan->center_freq),
01545                 sc->curchan->hw_value);
01546 
01547         if (ath5k_hw_gainf_calibrate(ah) == AR5K_RFGAIN_NEED_CHANGE) {
01548                 /*
01549                  * Rfgain is out of bounds, reset the chip
01550                  * to load new gain values.
01551                  */
01552                 ATH5K_DBG(sc, ATH5K_DEBUG_RESET, "calibration, resetting\n");
01553                 //ath5k_reset_wake(sc);
01554         }
01555         if (ath5k_hw_phy_calibrate(ah, sc->curchan))
01556                 ATH5K_ERR(sc, "calibration of channel %u failed\n",
01557                         ath5k_frequency_to_channel(
01558                                 sc->curchan->center_freq));
01559 #endif
01560 
01561         ah->ah_swi_mask = 0;
01562 }
01563 
01564 static int ath5k_hw_rix_to_bitrate(struct ath5k_softc *sc, int hw_rix)
01565 {
01566         int i;
01567 
01568         for (i = 0; i < ATH5K_NR_RATES; i++)
01569         {
01570                 if (ath5k_rates[i].hw_value == hw_rix)
01571                         return ath5k_rates[i].bitrate;
01572         }
01573 
01574         ATH5K_ERR(sc, "ath5k: invalid rix %02x\n", hw_rix);
01575         return 10; /* use lowest rate */
01576 }
01577 
01578 /**********************\
01579 * Interface functions *
01580 \**********************/
01581         int
01582 ath5k_recv (struct ath5k_softc *sc, frame_t *frame, const struct timespec *abs_timeout)
01583 {
01584         unsigned int sem_value;
01585 
01586         if (abs_timeout == NULL)
01587         {
01588                 if (sem_wait (&sc->rxring.sem))
01589                 {
01590                         ATH5K_ERR(sc, "sem_wait failed\n");
01591                         return -1;
01592                 }
01593         }
01594         else
01595         {
01596                 if ((sem_value = sem_timedwait (&sc->rxring.sem, abs_timeout)) != 0)
01597                 {
01598                         ATH5K_DBG(sc, ATH5K_DEBUG_TIMEOUT,
01599                                         "sem_timedwait timeout exceeded (%d)\n", sem_value);
01600                         return -2;
01601                 }
01602         }
01603 
01604         if (posix_intr_lock (sc->pdev->irq))
01605         {
01606                 ATH5K_ERR(sc, "posix_intr_lock failed\n");
01607                 return -3;
01608         }
01609         //----------------------------------------------
01610         ath5k_ring_extract (&sc->rxring, frame);
01611         /* Como hemos consumido el semaforo en el wait, abrirlo de nuevo si el
01612          * anillo no esta vacio */
01613         if (!ath5k_ring_empty (&sc->rxring))
01614         {
01615                 sem_getvalue (&sc->rxring.sem, &sem_value);
01616                 if (sem_value == 0)
01617                         sem_post (&sc->rxring.sem);
01618         }
01619         //----------------------------------------------
01620         if (posix_intr_unlock (sc->pdev->irq))
01621         {
01622                 ATH5K_ERR(sc, "posix_intr_lock failed\n");
01623                 return -4;
01624         }
01625 
01626         return 0;
01627 }
01628 
01629 /*
01630  * Contexto: UC
01631  *
01632  * Esta funcion transforma la cabecera ethernet en una 802.11, saca la primera
01633  * entrada de la lista sc->txbuf, y llama a ath5k_txbuf_setup pasandosela como
01634  * parametro (esa funcion se encarga de rellenar el descriptor y encolarla en
01635  * sc->txq)
01636  *
01637  * Hay que bloquear las interrupciones ya que el hardware lanza una interrupcion
01638  * cuando termina de enviar un elemento de la cola, y la ISR recoge esos 
01639  * elementos de sc->txq para volverlos a insertar al final de sc->txbuf.
01640  */
01641         int
01642 ath5k_send (struct ath5k_softc *sc, const unsigned char *buff, const int nbytes)
01643 {
01644         struct ath5k_buf *bf;
01645         struct sk_buff *skb;
01646         int hdrlen;
01647         int padsize;
01648 
01649         struct ethhdr *ethernet_hdr;
01650         unsigned short ethertype;
01651         struct ieee80211_hdr header;
01652         struct ieee80211_snap_hdr snap;
01653         const unsigned char *payload;
01654         int frame_control, data_len;
01655 
01656         /* Check data len */
01657         data_len = nbytes - ETH_HLEN;
01658         if (data_len > IEEE80211_MAX_DATA_LEN)
01659         {
01660                 ATH5K_ERR (NULL, "Data too large (%d B). Max size is %d.\n", data_len, IEEE80211_MAX_DATA_LEN);
01661                 return -1;
01662         }
01663         else
01664                 payload = buff + ETH_HLEN;
01665 
01666         /* Get the first entry from sc->txbuf */
01667         cli();
01668         if (list_empty(&sc->txbuf)) {
01669                 ATH5K_ERR(sc, "no further txbuf available, dropping packet\n");
01670                 sti();
01671                 return 0;
01672         }
01673         bf = list_first_entry(&sc->txbuf, struct ath5k_buf, list);
01674         list_del(&bf->list);
01675         sc->txbuf_len--;
01676         sti();
01677 
01678         skb = bf->skb;
01679 
01680         /* Fill IEEE 802.11 header */
01681         ethernet_hdr = (struct ethhdr *)buff;
01682         memcpy(header.addr1, ethernet_hdr->h_dest, ETH_ALEN);
01683         memcpy(header.addr2, ethernet_hdr->h_source, ETH_ALEN);
01684         memcpy(header.addr3, sc->ah->ah_bssid, ETH_ALEN);
01685 
01686         frame_control = IEEE80211_FTYPE_DATA | IEEE80211_STYPE_DATA;
01687         header.frame_control = cpu_to_le16(frame_control);
01688 
01689         hdrlen = 24;
01690 
01691         memcpy(skb_put(skb, hdrlen), &header, hdrlen);
01692 
01693         /* Copy SNAP and ethertype */
01694         snap.dsap = 0xaa;
01695         snap.ssap = 0xaa;
01696         snap.ctrl = 0x03;
01697         snap.oui[0] = 0x00;
01698         snap.oui[1] = 0x00;
01699         snap.oui[2] = 0x00;
01700         memcpy(skb_put(skb, SNAP_SIZE), &snap, SNAP_SIZE);
01701         ethertype = ethernet_hdr->h_proto;
01702         memcpy(skb_put(skb, sizeof(short)), &ethertype, sizeof(short));
01703 
01704         /* Copy payload */
01705         memcpy(skb_put(skb, data_len), payload, data_len);
01706 
01707         ath5k_debug_dump_skb(sc, skb, "TX  ", 1);
01708 
01709         /*
01710          * the hardware expects the header padded to 4 byte boundaries
01711          * if this is not the case we add the padding after the header
01712          */
01713         hdrlen = ath5k_get_hdrlen_from_skb(skb);
01714         padsize = ath5k_pad_size(hdrlen);
01715         if (padsize) {
01716                 if (skb_headroom(skb) < padsize) {
01717                         ATH5K_ERR(sc, "tx hdrlen not %%4: %d not enough"
01718                                   " headroom to pad %d\n", hdrlen, padsize);
01719                         return -1;
01720                 }
01721                 skb_push(skb, padsize);
01722                 memmove(skb->data, skb->data+padsize, hdrlen);
01723         }
01724 
01725 
01726         if (ath5k_txbuf_setup(sc, bf)) {
01727                 cli();
01728                 list_add_tail(&bf->list, &sc->txbuf);
01729                 sc->txbuf_len++;
01730                 sti();
01731                 return 0;
01732         }
01733 
01734         return 0;
01735 }
01736 
01737 /*
01738  * Reset the hardware.  If chan is not NULL, then also pause rx/tx
01739  * and change to the given channel.
01740  */
01741 static int
01742 ath5k_reset(struct ath5k_softc *sc, struct ieee80211_channel *chan)
01743 {
01744         struct ath5k_hw *ah = sc->ah;
01745         int ret;
01746 
01747         ATH5K_DBG(sc, ATH5K_DEBUG_RESET, "resetting\n");
01748 
01749         if (chan)
01750         {
01751                 ath5k_hw_set_imr(ah, 0);
01752                 ath5k_txq_cleanup(sc);
01753                 ath5k_rx_stop(sc);
01754 
01755                 sc->curchan = chan;
01756                 sc->curband = &sc->sbands[chan->band];
01757         }
01758 
01759         /* Change channel */
01760         ret = ath5k_hw_reset(ah, sc->curchan, true);
01761         if (ret) {
01762                 ATH5K_ERR(sc, "can't reset hardware (%d)\n", ret);
01763                 goto err;
01764         }
01765 
01766         /* Enable RX */
01767         ret = ath5k_rx_start(sc);
01768         if (ret) {
01769                 ATH5K_ERR(sc, "can't start recv logic\n");
01770                 goto err;
01771         }
01772 
01773         /* Enable interrupts */
01774         ath5k_hw_set_imr(ah, sc->imask);
01775 
01776         return 0;
01777 err:
01778         return ret;
01779 }
01780 
01781 int ath5k_config (struct ath5k_softc *sc,
01782            unsigned short freq,
01783            enum rates rate,
01784            unsigned char tx_power_dbm,
01785            enum ath5k_ant_mode antenna_mode)
01786 {
01787         struct ath5k_hw *ah = sc->ah;
01788         struct ieee80211_channel *target_channel;
01789         int rate_idx;
01790 
01791         /* Encontrar el canal */
01792         target_channel = ath5k_get_channel(sc, freq);
01793         if (target_channel == NULL)
01794         {
01795                 ATH5K_ERR(sc, "Invalid channel\n");
01796                 return -1;
01797         }
01798 
01799         /* Encontrar el bitrate */
01800         rate_idx = ath5k_get_rate_idx(sc, target_channel->band, rate);
01801         if (rate_idx < 0 || rate_idx > AR5K_MAX_RATES)
01802         {
01803                 ATH5K_ERR(sc, "Invalid rate\n");
01804                 return -1;
01805         }
01806 
01807         /* Configurar el rate */
01808         sc->tx_info.band = sc->curband->band;
01809         sc->tx_info.rate_idx = rate_idx;
01810         sc->tx_info.count = 1;
01811         sc->tx_info.wait_for_ack = false;
01812         sc->tx_info.use_short_preamble = false;
01813 
01814         if (sc->power_level != tx_power_dbm)
01815         {
01816                 sc->power_level = tx_power_dbm;
01817 
01818                 /* Half dB steps */
01819                 ath5k_hw_set_txpower_limit(ah, (tx_power_dbm * 2));
01820         }
01821 
01822         ath5k_hw_set_antenna_mode(ah, antenna_mode);
01823 
01824         /* Hacer un reset para aplicar los cambios */
01825         ath5k_reset(sc, target_channel);
01826 
01827         ATH5K_INFO(sc, "Freq %d Mhz, Rate (%d * 100) kps, Power %d dBm, Ant. mode %d\n",
01828                         freq, rate, tx_power_dbm, antenna_mode);
01829 
01830         return 0;
01831 }
01832 
01833 int ath5k_setTxPower(struct ath5k_softc *sc, int dbm){
01834         struct ath5k_hw *ah = sc->ah;
01835         ath5k_hw_set_txpower_limit(ah, (dbm * 2));
01836 }
01837 
01838 
01839 void ath5k_config_filter(struct ath5k_softc *sc, bool broadcast, bool control, bool promisc)
01840 {
01841         struct ath5k_hw *ah = sc->ah;
01842         unsigned int rfilt;
01843 
01844         rfilt = 0;
01845 
01846         /* Always enable Unicast */
01847         rfilt |= AR5K_RX_FILTER_UCAST;
01848 
01849         if (broadcast)
01850                 rfilt |= AR5K_RX_FILTER_BCAST;
01851 
01852         /* Allow control frames? */
01853         if (control)
01854                 rfilt |= AR5K_RX_FILTER_CONTROL;
01855 
01856         /* Promisc mode? */
01857         if (promisc)
01858         {
01859                 rfilt |= AR5K_RX_FILTER_PROM;
01860                 __set_bit (ATH_STAT_PROMISC, sc->status);
01861         }
01862         else
01863                 __clear_bit (ATH_STAT_PROMISC, sc->status);
01864 
01865         /* Set filters */
01866         ath5k_hw_set_rx_filter(ah, rfilt);
01867 
01868         /* Set multicast bits */
01869         ath5k_hw_set_mcast_filter(ah, 0, 0);
01870 
01871         /* Set the cached hw filter flags, this will alter actually be set in HW */
01872         sc->filter_flags = rfilt;
01873 }
01874 
01875 static struct ieee80211_channel * ath5k_get_channel(struct ath5k_softc *sc, unsigned int freq)
01876 {
01877         struct ieee80211_channel *aux;
01878         int i, n_channels;
01879 
01880         aux = NULL;
01881         if (freq < 3000)
01882         {
01883                 aux = sc->sbands[IEEE80211_BAND_2GHZ].channels;
01884                 n_channels = sc->sbands[IEEE80211_BAND_2GHZ].n_channels;
01885         }
01886         else if (sc->sbands[IEEE80211_BAND_5GHZ].channels != NULL)
01887         {
01888                 aux = sc->sbands[IEEE80211_BAND_5GHZ].channels;
01889                 n_channels = sc->sbands[IEEE80211_BAND_5GHZ].n_channels;
01890         }
01891 
01892         if (aux != NULL)
01893         {
01894                 for (i = 0; i < n_channels; i++, aux++)
01895                         if (aux->center_freq == freq)
01896                                 break;
01897         }
01898 
01899         return aux;
01900 }
01901 
01902 static int ath5k_get_rate_idx(struct ath5k_softc *sc, enum ieee80211_band band, enum rates rate)
01903 {
01904         struct ieee80211_rate *r;
01905         int i;
01906         bool valid = false;
01907 
01908         r = NULL;
01909 
01910         r = sc->sbands[band].bitrates;
01911 
01912         if (r != NULL)
01913                 for (i = 0; i < sc->curband->n_bitrates; i++, r++)
01914                 {
01915                         if (r->bitrate == rate)
01916                         {
01917                                 valid = true;
01918                                 break;
01919                         }
01920                 }
01921         if (valid)
01922                 return i;
01923         else
01924                 return -1;
01925 }
01926 
01927 int ath5k_config_tx_control (struct ath5k_softc *sc,
01928                 unsigned char count, bool wait_for_ack, bool use_short_preamble)
01929 {
01930         struct ieee80211_rate *rate;
01931 
01932         /* Clear flags */
01933         sc->tx_info.wait_for_ack = false;
01934         sc->tx_info.use_short_preamble = false;
01935 
01936         /* Set tx count if ack not received */
01937         sc->tx_info.count = count;
01938 
01939         /* Wait for ack flag */
01940         if (wait_for_ack)
01941                 sc->tx_info.wait_for_ack = true;
01942 
01943         /* Set rate code flags (short preamble) */
01944         rate = &sc->curband->bitrates[sc->tx_info.rate_idx];
01945         if (use_short_preamble && (rate->flags & IEEE80211_RATE_SHORT_PREAMBLE))
01946                 sc->tx_info.use_short_preamble = true;
01947 
01948         return 0;
01949 }
01950 
01951 int ath5k_config_disable_ack (struct ath5k_softc *sc, bool disable)
01952 {
01953         struct ath5k_hw *ah;
01954 
01955         if (sc == NULL)
01956                 return 1;
01957         else
01958                 ah = sc->ah;
01959 
01960         if (disable)
01961                 AR5K_REG_ENABLE_BITS(ah, AR5K_DIAG_SW, AR5K_DIAG_SW_DIS_ACK);
01962         else
01963                 AR5K_REG_DISABLE_BITS(ah, AR5K_DIAG_SW, AR5K_DIAG_SW_DIS_ACK);
01964 
01965         return 0;
01966 }
01967 
01968 
01969         inline void
01970 ath5k_config_debug_level(struct ath5k_softc *sc, unsigned int debug_mask)
01971 {
01972         sc->debug_level = debug_mask;
01973 }
01974 
01975         inline void
01976 ath5k_get_interface_mac(struct ath5k_softc *sc, unsigned char *mac)
01977 {
01978         ath5k_hw_get_lladdr(sc->ah, mac);
01979 }
01980 


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