reset.c
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2004-2008 Reyk Floeter <reyk@openbsd.org>
00003  * Copyright (c) 2006-2008 Nick Kossifidis <mickflemm@gmail.com>
00004  * Copyright (c) 2007-2008 Luis Rodriguez <mcgrof@winlab.rutgers.edu>
00005  * Copyright (c) 2007-2008 Pavel Roskin <proski@gnu.org>
00006  * Copyright (c) 2007-2008 Jiri Slaby <jirislaby@gmail.com>
00007  *
00008  * Permission to use, copy, modify, and distribute this software for any
00009  * purpose with or without fee is hereby granted, provided that the above
00010  * copyright notice and this permission notice appear in all copies.
00011  *
00012  * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
00013  * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
00014  * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
00015  * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
00016  * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
00017  * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
00018  * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
00019  *
00020  */
00021 
00022 #define _ATH5K_RESET
00023 
00024 /*****************************\
00025   Reset functions and helpers
00026 \*****************************/
00027 
00028 #include <linux/pci.h>          /* To determine if a card is pci-e */
00029 #include <linux/log2.h>
00030 #include "ath5k.h"
00031 #include "reg.h"
00032 #include "base.h"
00033 #include "debug.h"
00034 
00050 static inline int ath5k_hw_write_ofdm_timings(struct ath5k_hw *ah,
00051         struct ieee80211_channel *channel)
00052 {
00053         /* Get exponent and mantissa and set it */
00054         u32 coef_scaled, coef_exp, coef_man,
00055                 ds_coef_exp, ds_coef_man, clock;
00056 
00057         BUG_ON(!(ah->ah_version == AR5K_AR5212) ||
00058                 !(channel->hw_value & CHANNEL_OFDM));
00059 
00060         /* Get coefficient
00061          * ALGO: coef = (5 * clock * carrier_freq) / 2)
00062          * we scale coef by shifting clock value by 24 for
00063          * better precision since we use integers */
00064         /* TODO: Half/quarter rate */
00065         clock =  ath5k_hw_htoclock(1, channel->hw_value & CHANNEL_TURBO);
00066 
00067         coef_scaled = ((5 * (clock << 24)) / 2) / channel->center_freq;
00068 
00069         /* Get exponent
00070          * ALGO: coef_exp = 14 - highest set bit position */
00071         coef_exp = ilog2(coef_scaled);
00072 
00073         /* Doesn't make sense if it's zero*/
00074         if (!coef_scaled || !coef_exp)
00075                 return -EINVAL;
00076 
00077         /* Note: we've shifted coef_scaled by 24 */
00078         coef_exp = 14 - (coef_exp - 24);
00079 
00080 
00081         /* Get mantissa (significant digits)
00082          * ALGO: coef_mant = floor(coef_scaled* 2^coef_exp+0.5) */
00083         coef_man = coef_scaled +
00084                 (1 << (24 - coef_exp - 1));
00085 
00086         /* Calculate delta slope coefficient exponent
00087          * and mantissa (remove scaling) and set them on hw */
00088         ds_coef_man = coef_man >> (24 - coef_exp);
00089         ds_coef_exp = coef_exp - 16;
00090 
00091         AR5K_REG_WRITE_BITS(ah, AR5K_PHY_TIMING_3,
00092                 AR5K_PHY_TIMING_3_DSC_MAN, ds_coef_man);
00093         AR5K_REG_WRITE_BITS(ah, AR5K_PHY_TIMING_3,
00094                 AR5K_PHY_TIMING_3_DSC_EXP, ds_coef_exp);
00095 
00096         return 0;
00097 }
00098 
00099 
00100 /*
00101  * index into rates for control rates, we can set it up like this because
00102  * this is only used for AR5212 and we know it supports G mode
00103  */
00104 static const unsigned int control_rates[] =
00105         { 0, 1, 1, 1, 4, 4, 6, 6, 8, 8, 8, 8 };
00106 
00126 static inline void ath5k_hw_write_rate_duration(struct ath5k_hw *ah,
00127        unsigned int mode)
00128 {
00129         struct ath5k_softc *sc = ah->ah_sc;
00130         struct ieee80211_rate *rate;
00131         unsigned int i;
00132 
00133         /* Write rate duration table */
00134         for (i = 0; i < sc->sbands[IEEE80211_BAND_2GHZ].n_bitrates; i++) {
00135                 u32 reg;
00136                 u16 tx_time;
00137 
00138                 rate = &sc->sbands[IEEE80211_BAND_2GHZ].bitrates[control_rates[i]];
00139 
00140                 /* Set ACK timeout */
00141                 reg = AR5K_RATE_DUR(rate->hw_value);
00142 
00143                 /* An ACK frame consists of 10 bytes. If you add the FCS,
00144                  * which ieee80211_generic_frame_duration() adds,
00145                  * its 14 bytes. Note we use the control rate and not the
00146                  * actual rate for this rate. See mac80211 tx.c
00147                  * ieee80211_duration() for a brief description of
00148                  * what rate we should choose to TX ACKs. */
00149                 tx_time = le16_to_cpu(ath5k_generic_frame_duration(mode,
00150                                                         sc->tx_info.use_short_preamble, 10, rate->bitrate));
00151 
00152                 ath5k_hw_reg_write(ah, tx_time, reg);
00153 
00154                 if (!(rate->flags & IEEE80211_RATE_SHORT_PREAMBLE))
00155                         continue;
00156 
00157                 /*
00158                  * We're not distinguishing short preamble here,
00159                  * This is true, all we'll get is a longer value here
00160                  * which is not necessarilly bad. We could use
00161                  * export ieee80211_frame_duration() but that needs to be
00162                  * fixed first to be properly used by mac802111 drivers:
00163                  *
00164                  *  - remove erp stuff and let the routine figure ofdm
00165                  *    erp rates
00166                  *  - remove passing argument ieee80211_local as
00167                  *    drivers don't have access to it
00168                  *  - move drivers using ieee80211_generic_frame_duration()
00169                  *    to this
00170                  */
00171                 ath5k_hw_reg_write(ah, tx_time,
00172                         reg + (AR5K_SET_SHORT_PREAMBLE << 2));
00173         }
00174 }
00175 
00176 /*
00177  * Reset chipset
00178  */
00179 static int ath5k_hw_nic_reset(struct ath5k_hw *ah, u32 val)
00180 {
00181         int ret;
00182         u32 mask = val ? val : ~0U;
00183 
00184         ATH5K_TRACE(ah->ah_sc);
00185 
00186         /* Read-and-clear RX Descriptor Pointer*/
00187         ath5k_hw_reg_read(ah, AR5K_RXDP);
00188 
00189         /*
00190          * Reset the device and wait until success
00191          */
00192         ath5k_hw_reg_write(ah, val, AR5K_RESET_CTL);
00193 
00194         /* Wait at least 128 PCI clocks */
00195         udelay(15);
00196 
00197         if (ah->ah_version == AR5K_AR5210) {
00198                 val &= AR5K_RESET_CTL_PCU | AR5K_RESET_CTL_DMA
00199                         | AR5K_RESET_CTL_MAC | AR5K_RESET_CTL_PHY;
00200                 mask &= AR5K_RESET_CTL_PCU | AR5K_RESET_CTL_DMA
00201                         | AR5K_RESET_CTL_MAC | AR5K_RESET_CTL_PHY;
00202         } else {
00203                 val &= AR5K_RESET_CTL_PCU | AR5K_RESET_CTL_BASEBAND;
00204                 mask &= AR5K_RESET_CTL_PCU | AR5K_RESET_CTL_BASEBAND;
00205         }
00206 
00207         ret = ath5k_hw_register_timeout(ah, AR5K_RESET_CTL, mask, val, false);
00208 
00209         /*
00210          * Reset configuration register (for hw byte-swap). Note that this
00211          * is only set for big endian. We do the necessary magic in
00212          * AR5K_INIT_CFG.
00213          */
00214         if ((val & AR5K_RESET_CTL_PCU) == 0)
00215                 ath5k_hw_reg_write(ah, AR5K_INIT_CFG, AR5K_CFG);
00216 
00217         return ret;
00218 }
00219 
00220 /*
00221  * Sleep control
00222  */
00223 int ath5k_hw_set_power(struct ath5k_hw *ah, enum ath5k_power_mode mode,
00224                 bool set_chip, u16 sleep_duration)
00225 {
00226         unsigned int i;
00227         u32 staid, data;
00228 
00229         ATH5K_TRACE(ah->ah_sc);
00230         staid = ath5k_hw_reg_read(ah, AR5K_STA_ID1);
00231 
00232         switch (mode) {
00233         case AR5K_PM_AUTO:
00234                 staid &= ~AR5K_STA_ID1_DEFAULT_ANTENNA;
00235                 /* fallthrough */
00236         case AR5K_PM_NETWORK_SLEEP:
00237                 if (set_chip)
00238                         ath5k_hw_reg_write(ah,
00239                                 AR5K_SLEEP_CTL_SLE_ALLOW |
00240                                 sleep_duration,
00241                                 AR5K_SLEEP_CTL);
00242 
00243                 staid |= AR5K_STA_ID1_PWR_SV;
00244                 break;
00245 
00246         case AR5K_PM_FULL_SLEEP:
00247                 if (set_chip)
00248                         ath5k_hw_reg_write(ah, AR5K_SLEEP_CTL_SLE_SLP,
00249                                 AR5K_SLEEP_CTL);
00250 
00251                 staid |= AR5K_STA_ID1_PWR_SV;
00252                 break;
00253 
00254         case AR5K_PM_AWAKE:
00255 
00256                 staid &= ~AR5K_STA_ID1_PWR_SV;
00257 
00258                 if (!set_chip)
00259                         goto commit;
00260 
00261                 data = ath5k_hw_reg_read(ah, AR5K_SLEEP_CTL);
00262 
00263                 /* If card is down we 'll get 0xffff... so we
00264                  * need to clean this up before we write the register
00265                  */
00266                 if (data & 0xffc00000)
00267                         data = 0;
00268                 else
00269                         /* Preserve sleep duration etc */
00270                         data = data & ~AR5K_SLEEP_CTL_SLE;
00271 
00272                 ath5k_hw_reg_write(ah, data | AR5K_SLEEP_CTL_SLE_WAKE,
00273                                                         AR5K_SLEEP_CTL);
00274                 udelay(15);
00275 
00276                 for (i = 200; i > 0; i--) {
00277                         /* Check if the chip did wake up */
00278                         if ((ath5k_hw_reg_read(ah, AR5K_PCICFG) &
00279                                         AR5K_PCICFG_SPWR_DN) == 0)
00280                                 break;
00281 
00282                         /* Wait a bit and retry */
00283                         udelay(50);
00284                         ath5k_hw_reg_write(ah, data | AR5K_SLEEP_CTL_SLE_WAKE,
00285                                                         AR5K_SLEEP_CTL);
00286                 }
00287 
00288                 /* Fail if the chip didn't wake up */
00289                 if (i == 0)
00290                         return -EIO;
00291 
00292                 break;
00293 
00294         default:
00295                 return -EINVAL;
00296         }
00297 
00298 commit:
00299         ath5k_hw_reg_write(ah, staid, AR5K_STA_ID1);
00300 
00301         return 0;
00302 }
00303 
00304 /*
00305  * Put device on hold
00306  *
00307  * Put MAC and Baseband on warm reset and
00308  * keep that state (don't clean sleep control
00309  * register). After this MAC and Baseband are
00310  * disabled and a full reset is needed to come
00311  * back. This way we save as much power as possible
00312  * without puting the card on full sleep.
00313  */
00314 int ath5k_hw_on_hold(struct ath5k_hw *ah)
00315 {
00316         struct pci_dev *pdev = ah->ah_sc->pdev;
00317         u32 bus_flags;
00318         int ret;
00319 
00320         /* Make sure device is awake */
00321         ret = ath5k_hw_set_power(ah, AR5K_PM_AWAKE, true, 0);
00322         if (ret) {
00323                 ATH5K_ERR(ah->ah_sc, "failed to wakeup the MAC Chip\n");
00324                 return ret;
00325         }
00326 
00327         /*
00328          * Put chipset on warm reset...
00329          *
00330          * Note: puting PCI core on warm reset on PCI-E cards
00331          * results card to hang and always return 0xffff... so
00332          * we ingore that flag for PCI-E cards. On PCI cards
00333          * this flag gets cleared after 64 PCI clocks.
00334          */
00335         bus_flags = (pdev->is_pcie) ? 0 : AR5K_RESET_CTL_PCI;
00336 
00337         if (ah->ah_version == AR5K_AR5210) {
00338                 ret = ath5k_hw_nic_reset(ah, AR5K_RESET_CTL_PCU |
00339                         AR5K_RESET_CTL_MAC | AR5K_RESET_CTL_DMA |
00340                         AR5K_RESET_CTL_PHY | AR5K_RESET_CTL_PCI);
00341                         mdelay(2);
00342         } else {
00343                 ret = ath5k_hw_nic_reset(ah, AR5K_RESET_CTL_PCU |
00344                         AR5K_RESET_CTL_BASEBAND | bus_flags);
00345         }
00346 
00347         if (ret) {
00348                 ATH5K_ERR(ah->ah_sc, "failed to put device on warm reset\n");
00349                 return -EIO;
00350         }
00351 
00352         /* ...wakeup again!*/
00353         ret = ath5k_hw_set_power(ah, AR5K_PM_AWAKE, true, 0);
00354         if (ret) {
00355                 ATH5K_ERR(ah->ah_sc, "failed to put device on hold\n");
00356                 return ret;
00357         }
00358 
00359         return ret;
00360 }
00361 
00362 /*
00363  * Bring up MAC + PHY Chips and program PLL
00364  * TODO: Half/Quarter rate support
00365  */
00366 int ath5k_hw_nic_wakeup(struct ath5k_hw *ah, int flags, bool initial)
00367 {
00368         struct pci_dev *pdev = ah->ah_sc->pdev;
00369         u32 turbo, mode, clock, bus_flags;
00370         int ret;
00371 
00372         turbo = 0;
00373         mode = 0;
00374         clock = 0;
00375 
00376         ATH5K_TRACE(ah->ah_sc);
00377 
00378         /* Wakeup the device */
00379         ret = ath5k_hw_set_power(ah, AR5K_PM_AWAKE, true, 0);
00380         if (ret) {
00381                 ATH5K_ERR(ah->ah_sc, "failed to wakeup the MAC Chip\n");
00382                 return ret;
00383         }
00384 
00385         /*
00386          * Put chipset on warm reset...
00387          *
00388          * Note: puting PCI core on warm reset on PCI-E cards
00389          * results card to hang and always return 0xffff... so
00390          * we ingore that flag for PCI-E cards. On PCI cards
00391          * this flag gets cleared after 64 PCI clocks.
00392          */
00393         bus_flags = (pdev->is_pcie) ? 0 : AR5K_RESET_CTL_PCI;
00394 
00395         if (ah->ah_version == AR5K_AR5210) {
00396                 ret = ath5k_hw_nic_reset(ah, AR5K_RESET_CTL_PCU |
00397                         AR5K_RESET_CTL_MAC | AR5K_RESET_CTL_DMA |
00398                         AR5K_RESET_CTL_PHY | AR5K_RESET_CTL_PCI);
00399                         mdelay(2);
00400         } else {
00401                 ret = ath5k_hw_nic_reset(ah, AR5K_RESET_CTL_PCU |
00402                         AR5K_RESET_CTL_BASEBAND | bus_flags);
00403         }
00404 
00405         if (ret) {
00406                 ATH5K_ERR(ah->ah_sc, "failed to reset the MAC Chip\n");
00407                 return -EIO;
00408         }
00409 
00410         /* ...wakeup again!...*/
00411         ret = ath5k_hw_set_power(ah, AR5K_PM_AWAKE, true, 0);
00412         if (ret) {
00413                 ATH5K_ERR(ah->ah_sc, "failed to resume the MAC Chip\n");
00414                 return ret;
00415         }
00416 
00417         /* ...clear reset control register and pull device out of
00418          * warm reset */
00419         if (ath5k_hw_nic_reset(ah, 0)) {
00420                 ATH5K_ERR(ah->ah_sc, "failed to warm reset the MAC Chip\n");
00421                 return -EIO;
00422         }
00423 
00424         /* On initialization skip PLL programming since we don't have
00425          * a channel / mode set yet */
00426         if (initial)
00427                 return 0;
00428 
00429         if (ah->ah_version != AR5K_AR5210) {
00430                 /*
00431                  * Get channel mode flags
00432                  */
00433 
00434                 if (ah->ah_radio >= AR5K_RF5112) {
00435                         mode = AR5K_PHY_MODE_RAD_RF5112;
00436                         clock = AR5K_PHY_PLL_RF5112;
00437                 } else {
00438                         mode = AR5K_PHY_MODE_RAD_RF5111;        /*Zero*/
00439                         clock = AR5K_PHY_PLL_RF5111;            /*Zero*/
00440                 }
00441 
00442                 if (flags & CHANNEL_2GHZ) {
00443                         mode |= AR5K_PHY_MODE_FREQ_2GHZ;
00444                         clock |= AR5K_PHY_PLL_44MHZ;
00445 
00446                         if (flags & CHANNEL_CCK) {
00447                                 mode |= AR5K_PHY_MODE_MOD_CCK;
00448                         } else if (flags & CHANNEL_OFDM) {
00449                                 /* XXX Dynamic OFDM/CCK is not supported by the
00450                                  * AR5211 so we set MOD_OFDM for plain g (no
00451                                  * CCK headers) operation. We need to test
00452                                  * this, 5211 might support ofdm-only g after
00453                                  * all, there are also initial register values
00454                                  * in the code for g mode (see initvals.c). */
00455                                 if (ah->ah_version == AR5K_AR5211)
00456                                         mode |= AR5K_PHY_MODE_MOD_OFDM;
00457                                 else
00458                                         mode |= AR5K_PHY_MODE_MOD_DYN;
00459                         } else {
00460                                 ATH5K_ERR(ah->ah_sc,
00461                                         "invalid radio modulation mode\n");
00462                                 return -EINVAL;
00463                         }
00464                 } else if (flags & CHANNEL_5GHZ) {
00465                         mode |= AR5K_PHY_MODE_FREQ_5GHZ;
00466 
00467                         if (ah->ah_radio == AR5K_RF5413)
00468                                 clock = AR5K_PHY_PLL_40MHZ_5413;
00469                         else
00470                                 clock |= AR5K_PHY_PLL_40MHZ;
00471 
00472                         if (flags & CHANNEL_OFDM)
00473                                 mode |= AR5K_PHY_MODE_MOD_OFDM;
00474                         else {
00475                                 ATH5K_ERR(ah->ah_sc,
00476                                         "invalid radio modulation mode\n");
00477                                 return -EINVAL;
00478                         }
00479                 } else {
00480                         ATH5K_ERR(ah->ah_sc, "invalid radio frequency mode\n");
00481                         return -EINVAL;
00482                 }
00483 
00484                 if (flags & CHANNEL_TURBO)
00485                         turbo = AR5K_PHY_TURBO_MODE | AR5K_PHY_TURBO_SHORT;
00486         } else { /* Reset the device */
00487 
00488                 /* ...enable Atheros turbo mode if requested */
00489                 if (flags & CHANNEL_TURBO)
00490                         ath5k_hw_reg_write(ah, AR5K_PHY_TURBO_MODE,
00491                                         AR5K_PHY_TURBO);
00492         }
00493 
00494         if (ah->ah_version != AR5K_AR5210) {
00495 
00496                 /* ...update PLL if needed */
00497                 if (ath5k_hw_reg_read(ah, AR5K_PHY_PLL) != clock) {
00498                         ath5k_hw_reg_write(ah, clock, AR5K_PHY_PLL);
00499                         udelay(300);
00500                 }
00501 
00502                 /* ...set the PHY operating mode */
00503                 ath5k_hw_reg_write(ah, mode, AR5K_PHY_MODE);
00504                 ath5k_hw_reg_write(ah, turbo, AR5K_PHY_TURBO);
00505         }
00506 
00507         return 0;
00508 }
00509 
00510 /*
00511  * If there is an external 32KHz crystal available, use it
00512  * as ref. clock instead of 32/40MHz clock and baseband clocks
00513  * to save power during sleep or restore normal 32/40MHz
00514  * operation.
00515  *
00516  * XXX: When operating on 32KHz certain PHY registers (27 - 31,
00517  *      123 - 127) require delay on access.
00518  */
00519 static void ath5k_hw_set_sleep_clock(struct ath5k_hw *ah, bool enable)
00520 {
00521         struct ath5k_eeprom_info *ee = &ah->ah_capabilities.cap_eeprom;
00522         u32 scal, spending, usec32;
00523 
00524         /* Only set 32KHz settings if we have an external
00525          * 32KHz crystal present */
00526         if ((AR5K_EEPROM_HAS32KHZCRYSTAL(ee->ee_misc1) ||
00527         AR5K_EEPROM_HAS32KHZCRYSTAL_OLD(ee->ee_misc1)) &&
00528         enable) {
00529 
00530                 /* 1 usec/cycle */
00531                 AR5K_REG_WRITE_BITS(ah, AR5K_USEC_5211, AR5K_USEC_32, 1);
00532                 /* Set up tsf increment on each cycle */
00533                 AR5K_REG_WRITE_BITS(ah, AR5K_TSF_PARM, AR5K_TSF_PARM_INC, 61);
00534 
00535                 /* Set baseband sleep control registers
00536                  * and sleep control rate */
00537                 ath5k_hw_reg_write(ah, 0x1f, AR5K_PHY_SCR);
00538 
00539                 if ((ah->ah_radio == AR5K_RF5112) ||
00540                 (ah->ah_radio == AR5K_RF5413) ||
00541                 (ah->ah_mac_version == (AR5K_SREV_AR2417 >> 4)))
00542                         spending = 0x14;
00543                 else
00544                         spending = 0x18;
00545                 ath5k_hw_reg_write(ah, spending, AR5K_PHY_SPENDING);
00546 
00547                 if ((ah->ah_radio == AR5K_RF5112) ||
00548                 (ah->ah_radio == AR5K_RF5413) ||
00549                 (ah->ah_mac_version == (AR5K_SREV_AR2417 >> 4))) {
00550                         ath5k_hw_reg_write(ah, 0x26, AR5K_PHY_SLMT);
00551                         ath5k_hw_reg_write(ah, 0x0d, AR5K_PHY_SCAL);
00552                         ath5k_hw_reg_write(ah, 0x07, AR5K_PHY_SCLOCK);
00553                         ath5k_hw_reg_write(ah, 0x3f, AR5K_PHY_SDELAY);
00554                         AR5K_REG_WRITE_BITS(ah, AR5K_PCICFG,
00555                                 AR5K_PCICFG_SLEEP_CLOCK_RATE, 0x02);
00556                 } else {
00557                         ath5k_hw_reg_write(ah, 0x0a, AR5K_PHY_SLMT);
00558                         ath5k_hw_reg_write(ah, 0x0c, AR5K_PHY_SCAL);
00559                         ath5k_hw_reg_write(ah, 0x03, AR5K_PHY_SCLOCK);
00560                         ath5k_hw_reg_write(ah, 0x20, AR5K_PHY_SDELAY);
00561                         AR5K_REG_WRITE_BITS(ah, AR5K_PCICFG,
00562                                 AR5K_PCICFG_SLEEP_CLOCK_RATE, 0x03);
00563                 }
00564 
00565                 /* Enable sleep clock operation */
00566                 AR5K_REG_ENABLE_BITS(ah, AR5K_PCICFG,
00567                                 AR5K_PCICFG_SLEEP_CLOCK_EN);
00568 
00569         } else {
00570 
00571                 /* Disable sleep clock operation and
00572                  * restore default parameters */
00573                 AR5K_REG_DISABLE_BITS(ah, AR5K_PCICFG,
00574                                 AR5K_PCICFG_SLEEP_CLOCK_EN);
00575 
00576                 AR5K_REG_WRITE_BITS(ah, AR5K_PCICFG,
00577                                 AR5K_PCICFG_SLEEP_CLOCK_RATE, 0);
00578 
00579                 ath5k_hw_reg_write(ah, 0x1f, AR5K_PHY_SCR);
00580                 ath5k_hw_reg_write(ah, AR5K_PHY_SLMT_32MHZ, AR5K_PHY_SLMT);
00581 
00582                 if (ah->ah_mac_version == (AR5K_SREV_AR2417 >> 4))
00583                         scal = AR5K_PHY_SCAL_32MHZ_2417;
00584                 else if (ee->ee_is_hb63)
00585                         scal = AR5K_PHY_SCAL_32MHZ_HB63;
00586                 else
00587                         scal = AR5K_PHY_SCAL_32MHZ;
00588                 ath5k_hw_reg_write(ah, scal, AR5K_PHY_SCAL);
00589 
00590                 ath5k_hw_reg_write(ah, AR5K_PHY_SCLOCK_32MHZ, AR5K_PHY_SCLOCK);
00591                 ath5k_hw_reg_write(ah, AR5K_PHY_SDELAY_32MHZ, AR5K_PHY_SDELAY);
00592 
00593                 if ((ah->ah_radio == AR5K_RF5112) ||
00594                 (ah->ah_radio == AR5K_RF5413) ||
00595                 (ah->ah_mac_version == (AR5K_SREV_AR2417 >> 4)))
00596                         spending = 0x14;
00597                 else
00598                         spending = 0x18;
00599                 ath5k_hw_reg_write(ah, spending, AR5K_PHY_SPENDING);
00600 
00601                 if ((ah->ah_radio == AR5K_RF5112) ||
00602                 (ah->ah_radio == AR5K_RF5413))
00603                         usec32 = 39;
00604                 else
00605                         usec32 = 31;
00606                 AR5K_REG_WRITE_BITS(ah, AR5K_USEC_5211, AR5K_USEC_32, usec32);
00607 
00608                 AR5K_REG_WRITE_BITS(ah, AR5K_TSF_PARM, AR5K_TSF_PARM_INC, 1);
00609         }
00610         return;
00611 }
00612 
00613 /* TODO: Half/Quarter rate */
00614 static void ath5k_hw_tweak_initval_settings(struct ath5k_hw *ah,
00615                                 struct ieee80211_channel *channel)
00616 {
00617         if (ah->ah_version == AR5K_AR5212 &&
00618             ah->ah_phy_revision >= AR5K_SREV_PHY_5212A) {
00619 
00620                 /* Setup ADC control */
00621                 ath5k_hw_reg_write(ah,
00622                                 (AR5K_REG_SM(2,
00623                                 AR5K_PHY_ADC_CTL_INBUFGAIN_OFF) |
00624                                 AR5K_REG_SM(2,
00625                                 AR5K_PHY_ADC_CTL_INBUFGAIN_ON) |
00626                                 AR5K_PHY_ADC_CTL_PWD_DAC_OFF |
00627                                 AR5K_PHY_ADC_CTL_PWD_ADC_OFF),
00628                                 AR5K_PHY_ADC_CTL);
00629 
00630 
00631 
00632                 /* Disable barker RSSI threshold */
00633                 AR5K_REG_DISABLE_BITS(ah, AR5K_PHY_DAG_CCK_CTL,
00634                                 AR5K_PHY_DAG_CCK_CTL_EN_RSSI_THR);
00635 
00636                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_DAG_CCK_CTL,
00637                         AR5K_PHY_DAG_CCK_CTL_RSSI_THR, 2);
00638 
00639                 /* Set the mute mask */
00640                 ath5k_hw_reg_write(ah, 0x0000000f, AR5K_SEQ_MASK);
00641         }
00642 
00643         /* Clear PHY_BLUETOOTH to allow RX_CLEAR line debug */
00644         if (ah->ah_phy_revision >= AR5K_SREV_PHY_5212B)
00645                 ath5k_hw_reg_write(ah, 0, AR5K_PHY_BLUETOOTH);
00646 
00647         /* Enable DCU double buffering */
00648         if (ah->ah_phy_revision > AR5K_SREV_PHY_5212B)
00649                 AR5K_REG_DISABLE_BITS(ah, AR5K_TXCFG,
00650                                 AR5K_TXCFG_DCU_DBL_BUF_DIS);
00651 
00652         /* Set DAC/ADC delays */
00653         if (ah->ah_version == AR5K_AR5212) {
00654                 u32 scal;
00655                 struct ath5k_eeprom_info *ee = &ah->ah_capabilities.cap_eeprom;
00656                 if (ah->ah_mac_version == (AR5K_SREV_AR2417 >> 4))
00657                         scal = AR5K_PHY_SCAL_32MHZ_2417;
00658                 else if (ee->ee_is_hb63)
00659                         scal = AR5K_PHY_SCAL_32MHZ_HB63;
00660                 else
00661                         scal = AR5K_PHY_SCAL_32MHZ;
00662                 ath5k_hw_reg_write(ah, scal, AR5K_PHY_SCAL);
00663         }
00664 
00665         /* Set fast ADC */
00666         if ((ah->ah_radio == AR5K_RF5413) ||
00667         (ah->ah_mac_version == (AR5K_SREV_AR2417 >> 4))) {
00668                 u32 fast_adc = true;
00669 
00670                 if (channel->center_freq == 2462 ||
00671                 channel->center_freq == 2467)
00672                         fast_adc = 0;
00673 
00674                 /* Only update if needed */
00675                 if (ath5k_hw_reg_read(ah, AR5K_PHY_FAST_ADC) != fast_adc)
00676                                 ath5k_hw_reg_write(ah, fast_adc,
00677                                                 AR5K_PHY_FAST_ADC);
00678         }
00679 
00680         /* Fix for first revision of the RF5112 RF chipset */
00681         if (ah->ah_radio == AR5K_RF5112 &&
00682                         ah->ah_radio_5ghz_revision <
00683                         AR5K_SREV_RAD_5112A) {
00684                 u32 data;
00685                 ath5k_hw_reg_write(ah, AR5K_PHY_CCKTXCTL_WORLD,
00686                                 AR5K_PHY_CCKTXCTL);
00687                 if (channel->hw_value & CHANNEL_5GHZ)
00688                         data = 0xffb81020;
00689                 else
00690                         data = 0xffb80d20;
00691                 ath5k_hw_reg_write(ah, data, AR5K_PHY_FRAME_CTL);
00692         }
00693 
00694         if (ah->ah_mac_srev < AR5K_SREV_AR5211) {
00695                 u32 usec_reg;
00696                 /* 5311 has different tx/rx latency masks
00697                  * from 5211, since we deal 5311 the same
00698                  * as 5211 when setting initvals, shift
00699                  * values here to their proper locations */
00700                 usec_reg = ath5k_hw_reg_read(ah, AR5K_USEC_5211);
00701                 ath5k_hw_reg_write(ah, usec_reg & (AR5K_USEC_1 |
00702                                 AR5K_USEC_32 |
00703                                 AR5K_USEC_TX_LATENCY_5211 |
00704                                 AR5K_REG_SM(29,
00705                                 AR5K_USEC_RX_LATENCY_5210)),
00706                                 AR5K_USEC_5211);
00707                 /* Clear QCU/DCU clock gating register */
00708                 ath5k_hw_reg_write(ah, 0, AR5K_QCUDCU_CLKGT);
00709                 /* Set DAC/ADC delays */
00710                 ath5k_hw_reg_write(ah, 0x08, AR5K_PHY_SCAL);
00711                 /* Enable PCU FIFO corruption ECO */
00712                 AR5K_REG_ENABLE_BITS(ah, AR5K_DIAG_SW_5211,
00713                                         AR5K_DIAG_SW_ECO_ENABLE);
00714         }
00715 }
00716 
00717 static void ath5k_hw_commit_eeprom_settings(struct ath5k_hw *ah,
00718                 struct ieee80211_channel *channel, u8 *ant, u8 ee_mode)
00719 {
00720         struct ath5k_eeprom_info *ee = &ah->ah_capabilities.cap_eeprom;
00721         s16 cck_ofdm_pwr_delta;
00722 
00723         /* Adjust power delta for channel 14 */
00724         if (channel->center_freq == 2484)
00725                 cck_ofdm_pwr_delta =
00726                         ((ee->ee_cck_ofdm_power_delta -
00727                         ee->ee_scaled_cck_delta) * 2) / 10;
00728         else
00729                 cck_ofdm_pwr_delta =
00730                         (ee->ee_cck_ofdm_power_delta * 2) / 10;
00731 
00732         /* Set CCK to OFDM power delta on tx power
00733          * adjustment register */
00734         if (ah->ah_phy_revision >= AR5K_SREV_PHY_5212A) {
00735                 if (channel->hw_value == CHANNEL_G)
00736                         ath5k_hw_reg_write(ah,
00737                         AR5K_REG_SM((ee->ee_cck_ofdm_gain_delta * -1),
00738                                 AR5K_PHY_TX_PWR_ADJ_CCK_GAIN_DELTA) |
00739                         AR5K_REG_SM((cck_ofdm_pwr_delta * -1),
00740                                 AR5K_PHY_TX_PWR_ADJ_CCK_PCDAC_INDEX),
00741                                 AR5K_PHY_TX_PWR_ADJ);
00742                 else
00743                         ath5k_hw_reg_write(ah, 0, AR5K_PHY_TX_PWR_ADJ);
00744         } else {
00745                 /* For older revs we scale power on sw during tx power
00746                  * setup */
00747                 ah->ah_txpower.txp_cck_ofdm_pwr_delta = cck_ofdm_pwr_delta;
00748                 ah->ah_txpower.txp_cck_ofdm_gainf_delta =
00749                                                 ee->ee_cck_ofdm_gain_delta;
00750         }
00751 
00752         /* Set antenna idle switch table */
00753         AR5K_REG_WRITE_BITS(ah, AR5K_PHY_ANT_CTL,
00754                         AR5K_PHY_ANT_CTL_SWTABLE_IDLE,
00755                         (ah->ah_ant_ctl[ee_mode][0] |
00756                         AR5K_PHY_ANT_CTL_TXRX_EN));
00757 
00758         /* Set antenna switch tables */
00759         ath5k_hw_reg_write(ah, ah->ah_ant_ctl[ee_mode][ant[0]],
00760                 AR5K_PHY_ANT_SWITCH_TABLE_0);
00761         ath5k_hw_reg_write(ah, ah->ah_ant_ctl[ee_mode][ant[1]],
00762                 AR5K_PHY_ANT_SWITCH_TABLE_1);
00763 
00764         /* Noise floor threshold */
00765         ath5k_hw_reg_write(ah,
00766                 AR5K_PHY_NF_SVAL(ee->ee_noise_floor_thr[ee_mode]),
00767                 AR5K_PHY_NFTHRES);
00768 
00769         if ((channel->hw_value & CHANNEL_TURBO) &&
00770         (ah->ah_ee_version >= AR5K_EEPROM_VERSION_5_0)) {
00771                 /* Switch settling time (Turbo) */
00772                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_SETTLING,
00773                                 AR5K_PHY_SETTLING_SWITCH,
00774                                 ee->ee_switch_settling_turbo[ee_mode]);
00775 
00776                 /* Tx/Rx attenuation (Turbo) */
00777                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_GAIN,
00778                                 AR5K_PHY_GAIN_TXRX_ATTEN,
00779                                 ee->ee_atn_tx_rx_turbo[ee_mode]);
00780 
00781                 /* ADC/PGA desired size (Turbo) */
00782                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_DESIRED_SIZE,
00783                                 AR5K_PHY_DESIRED_SIZE_ADC,
00784                                 ee->ee_adc_desired_size_turbo[ee_mode]);
00785 
00786                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_DESIRED_SIZE,
00787                                 AR5K_PHY_DESIRED_SIZE_PGA,
00788                                 ee->ee_pga_desired_size_turbo[ee_mode]);
00789 
00790                 /* Tx/Rx margin (Turbo) */
00791                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_GAIN_2GHZ,
00792                                 AR5K_PHY_GAIN_2GHZ_MARGIN_TXRX,
00793                                 ee->ee_margin_tx_rx_turbo[ee_mode]);
00794 
00795         } else {
00796                 /* Switch settling time */
00797                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_SETTLING,
00798                                 AR5K_PHY_SETTLING_SWITCH,
00799                                 ee->ee_switch_settling[ee_mode]);
00800 
00801                 /* Tx/Rx attenuation */
00802                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_GAIN,
00803                                 AR5K_PHY_GAIN_TXRX_ATTEN,
00804                                 ee->ee_atn_tx_rx[ee_mode]);
00805 
00806                 /* ADC/PGA desired size */
00807                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_DESIRED_SIZE,
00808                                 AR5K_PHY_DESIRED_SIZE_ADC,
00809                                 ee->ee_adc_desired_size[ee_mode]);
00810 
00811                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_DESIRED_SIZE,
00812                                 AR5K_PHY_DESIRED_SIZE_PGA,
00813                                 ee->ee_pga_desired_size[ee_mode]);
00814 
00815                 /* Tx/Rx margin */
00816                 if (ah->ah_ee_version >= AR5K_EEPROM_VERSION_4_1)
00817                         AR5K_REG_WRITE_BITS(ah, AR5K_PHY_GAIN_2GHZ,
00818                                 AR5K_PHY_GAIN_2GHZ_MARGIN_TXRX,
00819                                 ee->ee_margin_tx_rx[ee_mode]);
00820         }
00821 
00822         /* XPA delays */
00823         ath5k_hw_reg_write(ah,
00824                 (ee->ee_tx_end2xpa_disable[ee_mode] << 24) |
00825                 (ee->ee_tx_end2xpa_disable[ee_mode] << 16) |
00826                 (ee->ee_tx_frm2xpa_enable[ee_mode] << 8) |
00827                 (ee->ee_tx_frm2xpa_enable[ee_mode]), AR5K_PHY_RF_CTL4);
00828 
00829         /* XLNA delay */
00830         AR5K_REG_WRITE_BITS(ah, AR5K_PHY_RF_CTL3,
00831                         AR5K_PHY_RF_CTL3_TXE2XLNA_ON,
00832                         ee->ee_tx_end2xlna_enable[ee_mode]);
00833 
00834         /* Thresh64 (ANI) */
00835         AR5K_REG_WRITE_BITS(ah, AR5K_PHY_NF,
00836                         AR5K_PHY_NF_THRESH62,
00837                         ee->ee_thr_62[ee_mode]);
00838 
00839 
00840         /* False detect backoff for channels
00841          * that have spur noise. Write the new
00842          * cyclic power RSSI threshold. */
00843         if (ath5k_hw_chan_has_spur_noise(ah, channel))
00844                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_OFDM_SELFCORR,
00845                                 AR5K_PHY_OFDM_SELFCORR_CYPWR_THR1,
00846                                 AR5K_INIT_CYCRSSI_THR1 +
00847                                 ee->ee_false_detect[ee_mode]);
00848         else
00849                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_OFDM_SELFCORR,
00850                                 AR5K_PHY_OFDM_SELFCORR_CYPWR_THR1,
00851                                 AR5K_INIT_CYCRSSI_THR1);
00852 
00853         /* I/Q correction
00854          * TODO: Per channel i/q infos ? */
00855         AR5K_REG_ENABLE_BITS(ah, AR5K_PHY_IQ,
00856                 AR5K_PHY_IQ_CORR_ENABLE |
00857                 (ee->ee_i_cal[ee_mode] << AR5K_PHY_IQ_CORR_Q_I_COFF_S) |
00858                 ee->ee_q_cal[ee_mode]);
00859 
00860         /* Heavy clipping -disable for now */
00861         if (ah->ah_ee_version >= AR5K_EEPROM_VERSION_5_1)
00862                 ath5k_hw_reg_write(ah, 0, AR5K_PHY_HEAVY_CLIP_ENABLE);
00863 
00864         return;
00865 }
00866 
00867 /*
00868  * Main reset function
00869  */
00870 int ath5k_hw_reset(struct ath5k_hw *ah,
00871         struct ieee80211_channel *channel, bool change_channel)
00872 {
00873         u32 s_seq[10], s_ant, s_led[3], staid1_flags, tsf_up, tsf_lo;
00874         u32 phy_tst1;
00875         u8 mode, freq, ee_mode, ant[2];
00876         int i, ret;
00877 
00878         ATH5K_TRACE(ah->ah_sc);
00879 
00880         s_ant = 0;
00881         ee_mode = 0;
00882         staid1_flags = 0;
00883         tsf_up = 0;
00884         tsf_lo = 0;
00885         freq = 0;
00886         mode = 0;
00887 
00888         /*
00889          * Save some registers before a reset
00890          */
00891         /*DCU/Antenna selection not available on 5210*/
00892         if (ah->ah_version != AR5K_AR5210) {
00893 
00894                 switch (channel->hw_value & CHANNEL_MODES) {
00895                 case CHANNEL_A:
00896                         mode = AR5K_MODE_11A;
00897                         freq = AR5K_INI_RFGAIN_5GHZ;
00898                         ee_mode = AR5K_EEPROM_MODE_11A;
00899                         break;
00900                 case CHANNEL_G:
00901                         mode = AR5K_MODE_11G;
00902                         freq = AR5K_INI_RFGAIN_2GHZ;
00903                         ee_mode = AR5K_EEPROM_MODE_11G;
00904                         break;
00905                 case CHANNEL_B:
00906                         mode = AR5K_MODE_11B;
00907                         freq = AR5K_INI_RFGAIN_2GHZ;
00908                         ee_mode = AR5K_EEPROM_MODE_11B;
00909                         break;
00910                 case CHANNEL_T:
00911                         mode = AR5K_MODE_11A_TURBO;
00912                         freq = AR5K_INI_RFGAIN_5GHZ;
00913                         ee_mode = AR5K_EEPROM_MODE_11A;
00914                         break;
00915                 case CHANNEL_TG:
00916                         if (ah->ah_version == AR5K_AR5211) {
00917                                 ATH5K_ERR(ah->ah_sc,
00918                                         "TurboG mode not available on 5211");
00919                                 return -EINVAL;
00920                         }
00921                         mode = AR5K_MODE_11G_TURBO;
00922                         freq = AR5K_INI_RFGAIN_2GHZ;
00923                         ee_mode = AR5K_EEPROM_MODE_11G;
00924                         break;
00925                 case CHANNEL_XR:
00926                         if (ah->ah_version == AR5K_AR5211) {
00927                                 ATH5K_ERR(ah->ah_sc,
00928                                         "XR mode not available on 5211");
00929                                 return -EINVAL;
00930                         }
00931                         mode = AR5K_MODE_XR;
00932                         freq = AR5K_INI_RFGAIN_5GHZ;
00933                         ee_mode = AR5K_EEPROM_MODE_11A;
00934                         break;
00935                 default:
00936                         ATH5K_ERR(ah->ah_sc,
00937                                 "invalid channel: %d\n", channel->center_freq);
00938                         return -EINVAL;
00939                 }
00940 
00941                 if (change_channel) {
00942                         /*
00943                          * Save frame sequence count
00944                          * For revs. after Oahu, only save
00945                          * seq num for DCU 0 (Global seq num)
00946                          */
00947                         if (ah->ah_mac_srev < AR5K_SREV_AR5211) {
00948 
00949                                 for (i = 0; i < 10; i++)
00950                                         s_seq[i] = ath5k_hw_reg_read(ah,
00951                                                 AR5K_QUEUE_DCU_SEQNUM(i));
00952 
00953                         } else {
00954                                 s_seq[0] = ath5k_hw_reg_read(ah,
00955                                                 AR5K_QUEUE_DCU_SEQNUM(0));
00956                         }
00957 
00958                         /* TSF accelerates on AR5211 durring reset
00959                          * As a workaround save it here and restore
00960                          * it later so that it's back in time after
00961                          * reset. This way it'll get re-synced on the
00962                          * next beacon without breaking ad-hoc.
00963                          *
00964                          * On AR5212 TSF is almost preserved across a
00965                          * reset so it stays back in time anyway and
00966                          * we don't have to save/restore it.
00967                          *
00968                          * XXX: Since this breaks power saving we have
00969                          * to disable power saving until we receive the
00970                          * next beacon, so we can resync beacon timers */
00971                         if (ah->ah_version == AR5K_AR5211) {
00972                                 tsf_up = ath5k_hw_reg_read(ah, AR5K_TSF_U32);
00973                                 tsf_lo = ath5k_hw_reg_read(ah, AR5K_TSF_L32);
00974                         }
00975                 }
00976 
00977                 /* Save default antenna */
00978                 s_ant = ath5k_hw_reg_read(ah, AR5K_DEFAULT_ANTENNA);
00979 
00980                 if (ah->ah_version == AR5K_AR5212) {
00981                         /* Restore normal 32/40MHz clock operation
00982                          * to avoid register access delay on certain
00983                          * PHY registers */
00984                         ath5k_hw_set_sleep_clock(ah, false);
00985 
00986                         /* Since we are going to write rf buffer
00987                          * check if we have any pending gain_F
00988                          * optimization settings */
00989                         if (change_channel && ah->ah_rf_banks != NULL)
00990                                 ath5k_hw_gainf_calibrate(ah);
00991                 }
00992         }
00993 
00994         /*GPIOs*/
00995         s_led[0] = ath5k_hw_reg_read(ah, AR5K_PCICFG) &
00996                                         AR5K_PCICFG_LEDSTATE;
00997         s_led[1] = ath5k_hw_reg_read(ah, AR5K_GPIOCR);
00998         s_led[2] = ath5k_hw_reg_read(ah, AR5K_GPIODO);
00999 
01000         /* AR5K_STA_ID1 flags, only preserve antenna
01001          * settings and ack/cts rate mode */
01002         staid1_flags = ath5k_hw_reg_read(ah, AR5K_STA_ID1) &
01003                         (AR5K_STA_ID1_DEFAULT_ANTENNA |
01004                         AR5K_STA_ID1_DESC_ANTENNA |
01005                         AR5K_STA_ID1_RTS_DEF_ANTENNA |
01006                         AR5K_STA_ID1_ACKCTS_6MB |
01007                         AR5K_STA_ID1_BASE_RATE_11B |
01008                         AR5K_STA_ID1_SELFGEN_DEF_ANT);
01009 
01010         /* Wakeup the device */
01011         ret = ath5k_hw_nic_wakeup(ah, channel->hw_value, false);
01012         if (ret)
01013                 return ret;
01014 
01015         /* PHY access enable */
01016         if (ah->ah_mac_srev >= AR5K_SREV_AR5211)
01017                 ath5k_hw_reg_write(ah, AR5K_PHY_SHIFT_5GHZ, AR5K_PHY(0));
01018         else
01019                 ath5k_hw_reg_write(ah, AR5K_PHY_SHIFT_5GHZ | 0x40,
01020                                                         AR5K_PHY(0));
01021 
01022         /* Write initial settings */
01023         ret = ath5k_hw_write_initvals(ah, mode, change_channel);
01024         if (ret)
01025                 return ret;
01026 
01027         /*
01028          * 5211/5212 Specific
01029          */
01030         if (ah->ah_version != AR5K_AR5210) {
01031 
01032                 /*
01033                  * Write initial RF gain settings
01034                  * This should work for both 5111/5112
01035                  */
01036                 ret = ath5k_hw_rfgain_init(ah, freq);
01037                 if (ret)
01038                         return ret;
01039 
01040                 mdelay(1);
01041 
01042                 /*
01043                  * Tweak initval settings for revised
01044                  * chipsets and add some more config
01045                  * bits
01046                  */
01047                 ath5k_hw_tweak_initval_settings(ah, channel);
01048 
01049                 /*
01050                  * Set TX power
01051                  */
01052                 ret = ath5k_hw_txpower(ah, channel, ee_mode,
01053                                         ah->ah_txpower.txp_max_pwr / 2);
01054                 if (ret)
01055                         return ret;
01056 
01057                 /* Write rate duration table only on AR5212 and if
01058                  * virtual interface has already been brought up
01059                  * XXX: rethink this after new mode changes to
01060                  * mac80211 are integrated */
01061                 if (ah->ah_version == AR5K_AR5212)
01062                         ath5k_hw_write_rate_duration(ah, mode);
01063 
01064                 /*
01065                  * Write RF buffer
01066                  */
01067                 ret = ath5k_hw_rfregs_init(ah, channel, mode);
01068                 if (ret)
01069                         return ret;
01070 
01071 
01072                 /* Write OFDM timings on 5212*/
01073                 if (ah->ah_version == AR5K_AR5212 &&
01074                         channel->hw_value & CHANNEL_OFDM) {
01075                         struct ath5k_eeprom_info *ee =
01076                                         &ah->ah_capabilities.cap_eeprom;
01077 
01078                         ret = ath5k_hw_write_ofdm_timings(ah, channel);
01079                         if (ret)
01080                                 return ret;
01081 
01082                         /* Note: According to docs we can have a newer
01083                          * EEPROM on old hardware, so we need to verify
01084                          * that our hardware is new enough to have spur
01085                          * mitigation registers (delta phase etc) */
01086                         if (ah->ah_mac_srev >= AR5K_SREV_AR5424 ||
01087                         (ah->ah_mac_srev >= AR5K_SREV_AR5424 &&
01088                         ee->ee_version >= AR5K_EEPROM_VERSION_5_3))
01089                                 ath5k_hw_set_spur_mitigation_filter(ah,
01090                                                                 channel);
01091                 }
01092 
01093                 /*Enable/disable 802.11b mode on 5111
01094                 (enable 2111 frequency converter + CCK)*/
01095                 if (ah->ah_radio == AR5K_RF5111) {
01096                         if (mode == AR5K_MODE_11B)
01097                                 AR5K_REG_ENABLE_BITS(ah, AR5K_TXCFG,
01098                                     AR5K_TXCFG_B_MODE);
01099                         else
01100                                 AR5K_REG_DISABLE_BITS(ah, AR5K_TXCFG,
01101                                     AR5K_TXCFG_B_MODE);
01102                 }
01103 
01104                 /*
01105                  * In case a fixed antenna was set as default
01106                  * use the same switch table twice.
01107                  */
01108                 if (ah->ah_ant_mode == AR5K_ANTMODE_FIXED_A)
01109                                 ant[0] = ant[1] = AR5K_ANT_SWTABLE_A;
01110                 else if (ah->ah_ant_mode == AR5K_ANTMODE_FIXED_B)
01111                                 ant[0] = ant[1] = AR5K_ANT_SWTABLE_B;
01112                 else {
01113                         ant[0] = AR5K_ANT_SWTABLE_A;
01114                         ant[1] = AR5K_ANT_SWTABLE_B;
01115                 }
01116 
01117                 /* Commit values from EEPROM */
01118                 ath5k_hw_commit_eeprom_settings(ah, channel, ant, ee_mode);
01119 
01120         } else {
01121                 /*
01122                  * For 5210 we do all initialization using
01123                  * initvals, so we don't have to modify
01124                  * any settings (5210 also only supports
01125                  * a/aturbo modes)
01126                  */
01127                 mdelay(1);
01128                 /* Disable phy and wait */
01129                 ath5k_hw_reg_write(ah, AR5K_PHY_ACT_DISABLE, AR5K_PHY_ACT);
01130                 mdelay(1);
01131         }
01132 
01133         /*
01134          * Restore saved values
01135          */
01136 
01137         /*DCU/Antenna selection not available on 5210*/
01138         if (ah->ah_version != AR5K_AR5210) {
01139 
01140                 if (change_channel) {
01141                         if (ah->ah_mac_srev < AR5K_SREV_AR5211) {
01142                                 for (i = 0; i < 10; i++)
01143                                         ath5k_hw_reg_write(ah, s_seq[i],
01144                                                 AR5K_QUEUE_DCU_SEQNUM(i));
01145                         } else {
01146                                 ath5k_hw_reg_write(ah, s_seq[0],
01147                                         AR5K_QUEUE_DCU_SEQNUM(0));
01148                         }
01149 
01150 
01151                         if (ah->ah_version == AR5K_AR5211) {
01152                                 ath5k_hw_reg_write(ah, tsf_up, AR5K_TSF_U32);
01153                                 ath5k_hw_reg_write(ah, tsf_lo, AR5K_TSF_L32);
01154                         }
01155                 }
01156 
01157                 ath5k_hw_reg_write(ah, s_ant, AR5K_DEFAULT_ANTENNA);
01158         }
01159 
01160         /* Ledstate */
01161         AR5K_REG_ENABLE_BITS(ah, AR5K_PCICFG, s_led[0]);
01162 
01163         /* Gpio settings */
01164         ath5k_hw_reg_write(ah, s_led[1], AR5K_GPIOCR);
01165         ath5k_hw_reg_write(ah, s_led[2], AR5K_GPIODO);
01166 
01167         /* Restore sta_id flags and preserve our mac address*/
01168         ath5k_hw_reg_write(ah, AR5K_LOW_ID(ah->ah_sta_id),
01169                                                 AR5K_STA_ID0);
01170         ath5k_hw_reg_write(ah, staid1_flags | AR5K_HIGH_ID(ah->ah_sta_id),
01171                                                 AR5K_STA_ID1);
01172 
01173 
01174         /*
01175          * Configure PCU
01176          */
01177 
01178         /* Restore bssid and bssid mask */
01179         ath5k_hw_set_associd(ah, ah->ah_bssid, 0);
01180 
01181         /* Set PCU config */
01182         ath5k_hw_set_opmode(ah);
01183 
01184         /* Clear any pending interrupts
01185          * PISR/SISR Not available on 5210 */
01186         if (ah->ah_version != AR5K_AR5210)
01187                 ath5k_hw_reg_write(ah, 0xffffffff, AR5K_PISR);
01188 
01189         /* Set RSSI/BRSSI thresholds
01190          *
01191          * Note: If we decide to set this value
01192          * dynamicaly, have in mind that when AR5K_RSSI_THR
01193          * register is read it might return 0x40 if we haven't
01194          * wrote anything to it plus BMISS RSSI threshold is zeroed.
01195          * So doing a save/restore procedure here isn't the right
01196          * choice. Instead store it on ath5k_hw */
01197         ath5k_hw_reg_write(ah, (AR5K_TUNE_RSSI_THRES |
01198                                 AR5K_TUNE_BMISS_THRES <<
01199                                 AR5K_RSSI_THR_BMISS_S),
01200                                 AR5K_RSSI_THR);
01201 
01202         /* MIC QoS support */
01203         if (ah->ah_mac_srev >= AR5K_SREV_AR2413) {
01204                 ath5k_hw_reg_write(ah, 0x000100aa, AR5K_MIC_QOS_CTL);
01205                 ath5k_hw_reg_write(ah, 0x00003210, AR5K_MIC_QOS_SEL);
01206         }
01207 
01208         /* QoS NOACK Policy */
01209         if (ah->ah_version == AR5K_AR5212) {
01210                 ath5k_hw_reg_write(ah,
01211                         AR5K_REG_SM(2, AR5K_QOS_NOACK_2BIT_VALUES) |
01212                         AR5K_REG_SM(5, AR5K_QOS_NOACK_BIT_OFFSET)  |
01213                         AR5K_REG_SM(0, AR5K_QOS_NOACK_BYTE_OFFSET),
01214                         AR5K_QOS_NOACK);
01215         }
01216 
01217 
01218         /*
01219          * Configure PHY
01220          */
01221 
01222         /* Set channel on PHY */
01223         ret = ath5k_hw_channel(ah, channel);
01224         if (ret)
01225                 return ret;
01226 
01227         /*
01228          * Enable the PHY and wait until completion
01229          * This includes BaseBand and Synthesizer
01230          * activation.
01231          */
01232         ath5k_hw_reg_write(ah, AR5K_PHY_ACT_ENABLE, AR5K_PHY_ACT);
01233 
01234         /*
01235          * On 5211+ read activation -> rx delay
01236          * and use it.
01237          *
01238          * TODO: Half/quarter rate support
01239          */
01240         if (ah->ah_version != AR5K_AR5210) {
01241                 u32 delay;
01242                 delay = ath5k_hw_reg_read(ah, AR5K_PHY_RX_DELAY) &
01243                         AR5K_PHY_RX_DELAY_M;
01244                 delay = (channel->hw_value & CHANNEL_CCK) ?
01245                         ((delay << 2) / 22) : (delay / 10);
01246 
01247                 udelay(100 + (2 * delay));
01248         } else {
01249                 mdelay(1);
01250         }
01251 
01252         /*
01253          * Perform ADC test to see if baseband is ready
01254          * Set tx hold and check adc test register
01255          */
01256         phy_tst1 = ath5k_hw_reg_read(ah, AR5K_PHY_TST1);
01257         ath5k_hw_reg_write(ah, AR5K_PHY_TST1_TXHOLD, AR5K_PHY_TST1);
01258         for (i = 0; i <= 20; i++) {
01259                 if (!(ath5k_hw_reg_read(ah, AR5K_PHY_ADC_TEST) & 0x10))
01260                         break;
01261                 udelay(200);
01262         }
01263         ath5k_hw_reg_write(ah, phy_tst1, AR5K_PHY_TST1);
01264 
01265         /*
01266          * Start automatic gain control calibration
01267          *
01268          * During AGC calibration RX path is re-routed to
01269          * a power detector so we don't receive anything.
01270          *
01271          * This method is used to calibrate some static offsets
01272          * used together with on-the fly I/Q calibration (the
01273          * one performed via ath5k_hw_phy_calibrate), that doesn't
01274          * interrupt rx path.
01275          *
01276          * While rx path is re-routed to the power detector we also
01277          * start a noise floor calibration, to measure the
01278          * card's noise floor (the noise we measure when we are not
01279          * transmiting or receiving anything).
01280          *
01281          * If we are in a noisy environment AGC calibration may time
01282          * out and/or noise floor calibration might timeout.
01283          */
01284         AR5K_REG_ENABLE_BITS(ah, AR5K_PHY_AGCCTL,
01285                                 AR5K_PHY_AGCCTL_CAL);
01286 
01287         /* At the same time start I/Q calibration for QAM constellation
01288          * -no need for CCK- */
01289         ah->ah_calibration = false;
01290         if (!(mode == AR5K_MODE_11B)) {
01291                 ah->ah_calibration = true;
01292                 AR5K_REG_WRITE_BITS(ah, AR5K_PHY_IQ,
01293                                 AR5K_PHY_IQ_CAL_NUM_LOG_MAX, 15);
01294                 AR5K_REG_ENABLE_BITS(ah, AR5K_PHY_IQ,
01295                                 AR5K_PHY_IQ_RUN);
01296         }
01297 
01298         /* Wait for gain calibration to finish (we check for I/Q calibration
01299          * during ath5k_phy_calibrate) */
01300         if (ath5k_hw_register_timeout(ah, AR5K_PHY_AGCCTL,
01301                         AR5K_PHY_AGCCTL_CAL, 0, false)) {
01302                 ATH5K_ERR(ah->ah_sc, "gain calibration timeout (%uMHz)\n",
01303                         channel->center_freq);
01304         }
01305 
01306         /*
01307          * If we run NF calibration before AGC, it always times out.
01308          * Binary HAL starts NF and AGC calibration at the same time
01309          * and only waits for AGC to finish. Also if AGC or NF cal.
01310          * times out, reset doesn't fail on binary HAL. I believe
01311          * that's wrong because since rx path is routed to a detector,
01312          * if cal. doesn't finish we won't have RX. Sam's HAL for AR5210/5211
01313          * enables noise floor calibration after offset calibration and if noise
01314          * floor calibration fails, reset fails. I believe that's
01315          * a better approach, we just need to find a polling interval
01316          * that suits best, even if reset continues we need to make
01317          * sure that rx path is ready.
01318          */
01319         ath5k_hw_noise_floor_calibration(ah, channel->center_freq);
01320 
01321         /* Restore antenna mode */
01322         ath5k_hw_set_antenna_mode(ah, ah->ah_ant_mode);
01323 
01324         /*
01325          * Configure QCUs/DCUs
01326          */
01327 
01328         /* TODO: HW Compression support for data queues */
01329         /* TODO: Burst prefetch for data queues */
01330 
01331         /*
01332          * Reset queues and start beacon timers at the end of the reset routine
01333          * This also sets QCU mask on each DCU for 1:1 qcu to dcu mapping
01334          * Note: If we want we can assign multiple qcus on one dcu.
01335          */
01336         for (i = 0; i < ah->ah_capabilities.cap_queues.q_tx_num; i++) {
01337                 ret = ath5k_hw_reset_tx_queue(ah, i);
01338                 if (ret) {
01339                         ATH5K_ERR(ah->ah_sc,
01340                                 "failed to reset TX queue #%d\n", i);
01341                         return ret;
01342                 }
01343         }
01344 
01345 
01346         /*
01347          * Configure DMA/Interrupts
01348          */
01349 
01350         /*
01351          * Set Rx/Tx DMA Configuration
01352          *
01353          * Set standard DMA size (128). Note that
01354          * a DMA size of 512 causes rx overruns and tx errors
01355          * on pci-e cards (tested on 5424 but since rx overruns
01356          * also occur on 5416/5418 with madwifi we set 128
01357          * for all PCI-E cards to be safe).
01358          *
01359          * XXX: need to check 5210 for this
01360          * TODO: Check out tx triger level, it's always 64 on dumps but I
01361          * guess we can tweak it and see how it goes ;-)
01362          */
01363         if (ah->ah_version != AR5K_AR5210) {
01364                 AR5K_REG_WRITE_BITS(ah, AR5K_TXCFG,
01365                         AR5K_TXCFG_SDMAMR, AR5K_DMASIZE_128B);
01366                 AR5K_REG_WRITE_BITS(ah, AR5K_RXCFG,
01367                         AR5K_RXCFG_SDMAMW, AR5K_DMASIZE_128B);
01368         }
01369 
01370         /* Pre-enable interrupts on 5211/5212*/
01371         if (ah->ah_version != AR5K_AR5210)
01372                 ath5k_hw_set_imr(ah, ah->ah_imr);
01373 
01374         /* Enable 32KHz clock function for AR5212+ chips
01375          * Set clocks to 32KHz operation and use an
01376          * external 32KHz crystal when sleeping if one
01377          * exists */
01378         if (ah->ah_version == AR5K_AR5212)
01379                         ath5k_hw_set_sleep_clock(ah, true);
01380 
01381         /*
01382          * Disable beacons and reset the register
01383          */
01384         AR5K_REG_DISABLE_BITS(ah, AR5K_BEACON, AR5K_BEACON_ENABLE |
01385                         AR5K_BEACON_RESET_TSF);
01386 
01387         return 0;
01388 }
01389 
01390 #undef _ATH5K_RESET


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