qcu.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) 2004-2008 Reyk Floeter <reyk@openbsd.org>
00034  * Copyright (c) 2006-2008 Nick Kossifidis <mickflemm@gmail.com>
00035  *
00036  * Permission to use, copy, modify, and distribute this software for any
00037  * purpose with or without fee is hereby granted, provided that the above
00038  * copyright notice and this permission notice appear in all copies.
00039  *
00040  * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
00041  * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
00042  * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
00043  * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
00044  * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
00045  * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
00046  * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
00047  *
00048  */
00049 
00050 /********************************************\
00051 Queue Control Unit, DFS Control Unit Functions
00052 \********************************************/
00053 
00054 #include "ath5k.h"
00055 #include "reg.h"
00056 #include "debug.h"
00057 #include "base.h"
00058 
00059 /*
00060  * Get properties for a transmit queue
00061  */
00062 int ath5k_hw_get_tx_queueprops(struct ath5k_hw *ah, int queue,
00063                 struct ath5k_txq_info *queue_info)
00064 {
00065         ATH5K_TRACE(ah->ah_sc);
00066         memcpy(queue_info, &ah->ah_txq[queue], sizeof(struct ath5k_txq_info));
00067         return 0;
00068 }
00069 
00070 /*
00071  * Set properties for a transmit queue
00072  */
00073 int ath5k_hw_set_tx_queueprops(struct ath5k_hw *ah, int queue,
00074                                 const struct ath5k_txq_info *queue_info)
00075 {
00076         ATH5K_TRACE(ah->ah_sc);
00077         AR5K_ASSERT_ENTRY(queue, ah->ah_capabilities.cap_queues.q_tx_num);
00078 
00079         if (ah->ah_txq[queue].tqi_type == AR5K_TX_QUEUE_INACTIVE)
00080                 return -EIO;
00081 
00082         memcpy(&ah->ah_txq[queue], queue_info, sizeof(struct ath5k_txq_info));
00083 
00084         /*XXX: Is this supported on 5210 ?*/
00085         if ((queue_info->tqi_type == AR5K_TX_QUEUE_DATA &&
00086                         ((queue_info->tqi_subtype == AR5K_WME_AC_VI) ||
00087                         (queue_info->tqi_subtype == AR5K_WME_AC_VO))) ||
00088                         queue_info->tqi_type == AR5K_TX_QUEUE_UAPSD)
00089                 ah->ah_txq[queue].tqi_flags |= AR5K_TXQ_FLAG_POST_FR_BKOFF_DIS;
00090 
00091         return 0;
00092 }
00093 
00094 /*
00095  * Initialize a transmit queue
00096  */
00097 int ath5k_hw_setup_tx_queue(struct ath5k_hw *ah, enum ath5k_tx_queue queue_type,
00098                 struct ath5k_txq_info *queue_info)
00099 {
00100         unsigned int queue;
00101         int ret;
00102 
00103         ATH5K_TRACE(ah->ah_sc);
00104 
00105         /*
00106          * Get queue by type
00107          */
00108         /*5210 only has 2 queues*/
00109         if (ah->ah_version == AR5K_AR5210) {
00110                 switch (queue_type) {
00111                 case AR5K_TX_QUEUE_DATA:
00112                         queue = AR5K_TX_QUEUE_ID_NOQCU_DATA;
00113                         break;
00114                 case AR5K_TX_QUEUE_BEACON:
00115                 case AR5K_TX_QUEUE_CAB:
00116                         queue = AR5K_TX_QUEUE_ID_NOQCU_BEACON;
00117                         break;
00118                 default:
00119                         return -EINVAL;
00120                 }
00121         } else {
00122                 switch (queue_type) {
00123                 case AR5K_TX_QUEUE_DATA:
00124                         for (queue = AR5K_TX_QUEUE_ID_DATA_MIN;
00125                                 ah->ah_txq[queue].tqi_type !=
00126                                 AR5K_TX_QUEUE_INACTIVE; queue++) {
00127 
00128                                 if (queue > AR5K_TX_QUEUE_ID_DATA_MAX)
00129                                         return -EINVAL;
00130                         }
00131                         break;
00132                 case AR5K_TX_QUEUE_UAPSD:
00133                         queue = AR5K_TX_QUEUE_ID_UAPSD;
00134                         break;
00135                 case AR5K_TX_QUEUE_BEACON:
00136                         queue = AR5K_TX_QUEUE_ID_BEACON;
00137                         break;
00138                 case AR5K_TX_QUEUE_CAB:
00139                         queue = AR5K_TX_QUEUE_ID_CAB;
00140                         break;
00141                 case AR5K_TX_QUEUE_XR_DATA:
00142                         if (ah->ah_version != AR5K_AR5212)
00143                                 ATH5K_ERR(ah->ah_sc,
00144                                         "XR data queues only supported in"
00145                                         " 5212!\n");
00146                         queue = AR5K_TX_QUEUE_ID_XR_DATA;
00147                         break;
00148                 default:
00149                         return -EINVAL;
00150                 }
00151         }
00152 
00153         /*
00154          * Setup internal queue structure
00155          */
00156         memset(&ah->ah_txq[queue], 0, sizeof(struct ath5k_txq_info));
00157         ah->ah_txq[queue].tqi_type = queue_type;
00158 
00159         if (queue_info != NULL) {
00160                 queue_info->tqi_type = queue_type;
00161                 ret = ath5k_hw_set_tx_queueprops(ah, queue, queue_info);
00162                 if (ret)
00163                         return ret;
00164         }
00165 
00166         /*
00167          * We use ah_txq_status to hold a temp value for
00168          * the Secondary interrupt mask registers on 5211+
00169          * check out ath5k_hw_reset_tx_queue
00170          */
00171         AR5K_Q_ENABLE_BITS(ah->ah_txq_status, queue);
00172 
00173         return queue;
00174 }
00175 
00176 /*
00177  * Get number of pending frames
00178  * for a specific queue [5211+]
00179  */
00180 u32 ath5k_hw_num_tx_pending(struct ath5k_hw *ah, unsigned int queue)
00181 {
00182         u32 pending;
00183         ATH5K_TRACE(ah->ah_sc);
00184         AR5K_ASSERT_ENTRY(queue, ah->ah_capabilities.cap_queues.q_tx_num);
00185 
00186         /* Return if queue is declared inactive */
00187         if (ah->ah_txq[queue].tqi_type == AR5K_TX_QUEUE_INACTIVE)
00188                 return false;
00189 
00190         /* XXX: How about AR5K_CFG_TXCNT ? */
00191         if (ah->ah_version == AR5K_AR5210)
00192                 return false;
00193 
00194         pending = ath5k_hw_reg_read(ah, AR5K_QUEUE_STATUS(queue));
00195         pending &= AR5K_QCU_STS_FRMPENDCNT;
00196 
00197         /* It's possible to have no frames pending even if TXE
00198          * is set. To indicate that q has not stopped return
00199          * true */
00200         if (!pending && AR5K_REG_READ_Q(ah, AR5K_QCU_TXE, queue))
00201                 return true;
00202 
00203         return pending;
00204 }
00205 
00206 /*
00207  * Set a transmit queue inactive
00208  */
00209 void ath5k_hw_release_tx_queue(struct ath5k_hw *ah, unsigned int queue)
00210 {
00211         ATH5K_TRACE(ah->ah_sc);
00212         if (WARN_ON(queue >= ah->ah_capabilities.cap_queues.q_tx_num))
00213                 return;
00214 
00215         /* This queue will be skipped in further operations */
00216         ah->ah_txq[queue].tqi_type = AR5K_TX_QUEUE_INACTIVE;
00217         /*For SIMR setup*/
00218         AR5K_Q_DISABLE_BITS(ah->ah_txq_status, queue);
00219 }
00220 
00221 /*
00222  * Set DFS properties for a transmit queue on DCU
00223  */
00224 int ath5k_hw_reset_tx_queue(struct ath5k_hw *ah, unsigned int queue)
00225 {
00226         u32 cw_min, cw_max, retry_lg, retry_sh;
00227         struct ath5k_txq_info *tq = &ah->ah_txq[queue];
00228 
00229         ATH5K_TRACE(ah->ah_sc);
00230         AR5K_ASSERT_ENTRY(queue, ah->ah_capabilities.cap_queues.q_tx_num);
00231 
00232         tq = &ah->ah_txq[queue];
00233 
00234         if (tq->tqi_type == AR5K_TX_QUEUE_INACTIVE)
00235                 return 0;
00236 
00237         if (ah->ah_version == AR5K_AR5210) {
00238                 /* Only handle data queues, others will be ignored */
00239                 if (tq->tqi_type != AR5K_TX_QUEUE_DATA)
00240                         return 0;
00241 
00242                 /* Set Slot time */
00243                 ath5k_hw_reg_write(ah, ah->ah_turbo ?
00244                         AR5K_INIT_SLOT_TIME_TURBO : AR5K_INIT_SLOT_TIME,
00245                         AR5K_SLOT_TIME);
00246                 /* Set ACK_CTS timeout */
00247                 ath5k_hw_reg_write(ah, ah->ah_turbo ?
00248                         AR5K_INIT_ACK_CTS_TIMEOUT_TURBO :
00249                         AR5K_INIT_ACK_CTS_TIMEOUT, AR5K_SLOT_TIME);
00250                 /* Set Transmit Latency */
00251                 ath5k_hw_reg_write(ah, ah->ah_turbo ?
00252                         AR5K_INIT_TRANSMIT_LATENCY_TURBO :
00253                         AR5K_INIT_TRANSMIT_LATENCY, AR5K_USEC_5210);
00254 
00255                 /* Set IFS0 */
00256                 if (ah->ah_turbo) {
00257                          ath5k_hw_reg_write(ah, ((AR5K_INIT_SIFS_TURBO +
00258                                 (ah->ah_aifs + tq->tqi_aifs) *
00259                                 AR5K_INIT_SLOT_TIME_TURBO) <<
00260                                 AR5K_IFS0_DIFS_S) | AR5K_INIT_SIFS_TURBO,
00261                                 AR5K_IFS0);
00262                 } else {
00263                         ath5k_hw_reg_write(ah, ((AR5K_INIT_SIFS +
00264                                 (ah->ah_aifs + tq->tqi_aifs) *
00265                                 AR5K_INIT_SLOT_TIME) << AR5K_IFS0_DIFS_S) |
00266                                 AR5K_INIT_SIFS, AR5K_IFS0);
00267                 }
00268 
00269                 /* Set IFS1 */
00270                 ath5k_hw_reg_write(ah, ah->ah_turbo ?
00271                         AR5K_INIT_PROTO_TIME_CNTRL_TURBO :
00272                         AR5K_INIT_PROTO_TIME_CNTRL, AR5K_IFS1);
00273                 /* Set AR5K_PHY_SETTLING */
00274                 ath5k_hw_reg_write(ah, ah->ah_turbo ?
00275                         (ath5k_hw_reg_read(ah, AR5K_PHY_SETTLING) & ~0x7F)
00276                         | 0x38 :
00277                         (ath5k_hw_reg_read(ah, AR5K_PHY_SETTLING) & ~0x7F)
00278                         | 0x1C,
00279                         AR5K_PHY_SETTLING);
00280                 /* Set Frame Control Register */
00281                 ath5k_hw_reg_write(ah, ah->ah_turbo ?
00282                         (AR5K_PHY_FRAME_CTL_INI | AR5K_PHY_TURBO_MODE |
00283                         AR5K_PHY_TURBO_SHORT | 0x2020) :
00284                         (AR5K_PHY_FRAME_CTL_INI | 0x1020),
00285                         AR5K_PHY_FRAME_CTL_5210);
00286         }
00287 
00288         /*
00289          * Calculate cwmin/max by channel mode
00290          */
00291         cw_min = ah->ah_cw_min = AR5K_TUNE_CWMIN;
00292         cw_max = ah->ah_cw_max = AR5K_TUNE_CWMAX;
00293         ah->ah_aifs = AR5K_TUNE_AIFS;
00294         /*XR is only supported on 5212*/
00295         if (IS_CHAN_XR(ah->ah_current_channel) &&
00296                         ah->ah_version == AR5K_AR5212) {
00297                 cw_min = ah->ah_cw_min = AR5K_TUNE_CWMIN_XR;
00298                 cw_max = ah->ah_cw_max = AR5K_TUNE_CWMAX_XR;
00299                 ah->ah_aifs = AR5K_TUNE_AIFS_XR;
00300         /*B mode is not supported on 5210*/
00301         } else if (IS_CHAN_B(ah->ah_current_channel) &&
00302                         ah->ah_version != AR5K_AR5210) {
00303                 cw_min = ah->ah_cw_min = AR5K_TUNE_CWMIN_11B;
00304                 cw_max = ah->ah_cw_max = AR5K_TUNE_CWMAX_11B;
00305                 ah->ah_aifs = AR5K_TUNE_AIFS_11B;
00306         }
00307 
00308         cw_min = 1;
00309         while (cw_min < ah->ah_cw_min)
00310                 cw_min = (cw_min << 1) | 1;
00311 
00312         cw_min = tq->tqi_cw_min < 0 ? (cw_min >> (-tq->tqi_cw_min)) :
00313                 ((cw_min << tq->tqi_cw_min) + (1 << tq->tqi_cw_min) - 1);
00314         cw_max = tq->tqi_cw_max < 0 ? (cw_max >> (-tq->tqi_cw_max)) :
00315                 ((cw_max << tq->tqi_cw_max) + (1 << tq->tqi_cw_max) - 1);
00316 
00317         /*
00318          * Calculate and set retry limits
00319          */
00320         if (ah->ah_software_retry) {
00321                 /* XXX Need to test this */
00322                 retry_lg = ah->ah_limit_tx_retries;
00323                 retry_sh = retry_lg = retry_lg > AR5K_DCU_RETRY_LMT_SH_RETRY ?
00324                         AR5K_DCU_RETRY_LMT_SH_RETRY : retry_lg;
00325         } else {
00326                 retry_lg = AR5K_INIT_LG_RETRY;
00327                 retry_sh = AR5K_INIT_SH_RETRY;
00328         }
00329 
00330         /*No QCU/DCU [5210]*/
00331         if (ah->ah_version == AR5K_AR5210) {
00332                 ath5k_hw_reg_write(ah,
00333                         (cw_min << AR5K_NODCU_RETRY_LMT_CW_MIN_S)
00334                         | AR5K_REG_SM(AR5K_INIT_SLG_RETRY,
00335                                 AR5K_NODCU_RETRY_LMT_SLG_RETRY)
00336                         | AR5K_REG_SM(AR5K_INIT_SSH_RETRY,
00337                                 AR5K_NODCU_RETRY_LMT_SSH_RETRY)
00338                         | AR5K_REG_SM(retry_lg, AR5K_NODCU_RETRY_LMT_LG_RETRY)
00339                         | AR5K_REG_SM(retry_sh, AR5K_NODCU_RETRY_LMT_SH_RETRY),
00340                         AR5K_NODCU_RETRY_LMT);
00341         } else {
00342                 /*QCU/DCU [5211+]*/
00343                 ath5k_hw_reg_write(ah,
00344                         AR5K_REG_SM(AR5K_INIT_SLG_RETRY,
00345                                 AR5K_DCU_RETRY_LMT_SLG_RETRY) |
00346                         AR5K_REG_SM(AR5K_INIT_SSH_RETRY,
00347                                 AR5K_DCU_RETRY_LMT_SSH_RETRY) |
00348                         AR5K_REG_SM(retry_lg, AR5K_DCU_RETRY_LMT_LG_RETRY) |
00349                         AR5K_REG_SM(retry_sh, AR5K_DCU_RETRY_LMT_SH_RETRY),
00350                         AR5K_QUEUE_DFS_RETRY_LIMIT(queue));
00351 
00352         /*===Rest is also for QCU/DCU only [5211+]===*/
00353 
00354                 /*
00355                  * Set initial content window (cw_min/cw_max)
00356                  * and arbitrated interframe space (aifs)...
00357                  */
00358                 ath5k_hw_reg_write(ah,
00359                         AR5K_REG_SM(cw_min, AR5K_DCU_LCL_IFS_CW_MIN) |
00360                         AR5K_REG_SM(cw_max, AR5K_DCU_LCL_IFS_CW_MAX) |
00361                         AR5K_REG_SM(ah->ah_aifs + tq->tqi_aifs,
00362                                 AR5K_DCU_LCL_IFS_AIFS),
00363                         AR5K_QUEUE_DFS_LOCAL_IFS(queue));
00364 
00365                 /*
00366                  * Set misc registers
00367                  */
00368                 /* Enable DCU early termination for this queue */
00369                 AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_MISC(queue),
00370                                         AR5K_QCU_MISC_DCU_EARLY);
00371 
00372                 /* Enable DCU to wait for next fragment from QCU */
00373                 AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_DFS_MISC(queue),
00374                                         AR5K_DCU_MISC_FRAG_WAIT);
00375 
00376                 /* On Maui and Spirit use the global seqnum on DCU */
00377                 if (ah->ah_mac_version < AR5K_SREV_AR5211)
00378                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_DFS_MISC(queue),
00379                                                 AR5K_DCU_MISC_SEQNUM_CTL);
00380 
00381                 if (tq->tqi_cbr_period) {
00382                         ath5k_hw_reg_write(ah, AR5K_REG_SM(tq->tqi_cbr_period,
00383                                 AR5K_QCU_CBRCFG_INTVAL) |
00384                                 AR5K_REG_SM(tq->tqi_cbr_overflow_limit,
00385                                 AR5K_QCU_CBRCFG_ORN_THRES),
00386                                 AR5K_QUEUE_CBRCFG(queue));
00387                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_MISC(queue),
00388                                 AR5K_QCU_MISC_FRSHED_CBR);
00389                         if (tq->tqi_cbr_overflow_limit)
00390                                 AR5K_REG_ENABLE_BITS(ah,
00391                                         AR5K_QUEUE_MISC(queue),
00392                                         AR5K_QCU_MISC_CBR_THRES_ENABLE);
00393                 }
00394 
00395                 if (tq->tqi_ready_time &&
00396                 (tq->tqi_type != AR5K_TX_QUEUE_CAB))
00397                         ath5k_hw_reg_write(ah, AR5K_REG_SM(tq->tqi_ready_time,
00398                                 AR5K_QCU_RDYTIMECFG_INTVAL) |
00399                                 AR5K_QCU_RDYTIMECFG_ENABLE,
00400                                 AR5K_QUEUE_RDYTIMECFG(queue));
00401 
00402                 if (tq->tqi_burst_time) {
00403                         ath5k_hw_reg_write(ah, AR5K_REG_SM(tq->tqi_burst_time,
00404                                 AR5K_DCU_CHAN_TIME_DUR) |
00405                                 AR5K_DCU_CHAN_TIME_ENABLE,
00406                                 AR5K_QUEUE_DFS_CHANNEL_TIME(queue));
00407 
00408                         if (tq->tqi_flags
00409                         & AR5K_TXQ_FLAG_RDYTIME_EXP_POLICY_ENABLE)
00410                                 AR5K_REG_ENABLE_BITS(ah,
00411                                         AR5K_QUEUE_MISC(queue),
00412                                         AR5K_QCU_MISC_RDY_VEOL_POLICY);
00413                 }
00414 
00415                 if (tq->tqi_flags & AR5K_TXQ_FLAG_BACKOFF_DISABLE)
00416                         ath5k_hw_reg_write(ah, AR5K_DCU_MISC_POST_FR_BKOFF_DIS,
00417                                 AR5K_QUEUE_DFS_MISC(queue));
00418 
00419                 if (tq->tqi_flags & AR5K_TXQ_FLAG_FRAG_BURST_BACKOFF_ENABLE)
00420                         ath5k_hw_reg_write(ah, AR5K_DCU_MISC_BACKOFF_FRAG,
00421                                 AR5K_QUEUE_DFS_MISC(queue));
00422 
00423                 /*
00424                  * Set registers by queue type
00425                  */
00426                 switch (tq->tqi_type) {
00427                 case AR5K_TX_QUEUE_BEACON:
00428                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_MISC(queue),
00429                                 AR5K_QCU_MISC_FRSHED_DBA_GT |
00430                                 AR5K_QCU_MISC_CBREXP_BCN_DIS |
00431                                 AR5K_QCU_MISC_BCN_ENABLE);
00432 
00433                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_DFS_MISC(queue),
00434                                 (AR5K_DCU_MISC_ARBLOCK_CTL_GLOBAL <<
00435                                 AR5K_DCU_MISC_ARBLOCK_CTL_S) |
00436                                 AR5K_DCU_MISC_ARBLOCK_IGNORE |
00437                                 AR5K_DCU_MISC_POST_FR_BKOFF_DIS |
00438                                 AR5K_DCU_MISC_BCN_ENABLE);
00439                         break;
00440 
00441                 case AR5K_TX_QUEUE_CAB:
00442                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_MISC(queue),
00443                                 AR5K_QCU_MISC_FRSHED_BCN_SENT_GT |
00444                                 AR5K_QCU_MISC_CBREXP_DIS |
00445                                 AR5K_QCU_MISC_CBREXP_BCN_DIS);
00446 
00447                         ath5k_hw_reg_write(ah, ((AR5K_TUNE_BEACON_INTERVAL -
00448                                 (AR5K_TUNE_SW_BEACON_RESP -
00449                                 AR5K_TUNE_DMA_BEACON_RESP) -
00450                                 AR5K_TUNE_ADDITIONAL_SWBA_BACKOFF) * 1024) |
00451                                 AR5K_QCU_RDYTIMECFG_ENABLE,
00452                                 AR5K_QUEUE_RDYTIMECFG(queue));
00453 
00454                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_DFS_MISC(queue),
00455                                 (AR5K_DCU_MISC_ARBLOCK_CTL_GLOBAL <<
00456                                 AR5K_DCU_MISC_ARBLOCK_CTL_S));
00457                         break;
00458 
00459                 case AR5K_TX_QUEUE_UAPSD:
00460                         AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_MISC(queue),
00461                                 AR5K_QCU_MISC_CBREXP_DIS);
00462                         break;
00463 
00464                 case AR5K_TX_QUEUE_DATA:
00465                 default:
00466                         break;
00467                 }
00468 
00469                 /* TODO: Handle frame compression */
00470 
00471                 /*
00472                  * Enable interrupts for this tx queue
00473                  * in the secondary interrupt mask registers
00474                  */
00475                 if (tq->tqi_flags & AR5K_TXQ_FLAG_TXOKINT_ENABLE)
00476                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_txok, queue);
00477 
00478                 if (tq->tqi_flags & AR5K_TXQ_FLAG_TXERRINT_ENABLE)
00479                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_txerr, queue);
00480 
00481                 if (tq->tqi_flags & AR5K_TXQ_FLAG_TXURNINT_ENABLE)
00482                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_txurn, queue);
00483 
00484                 if (tq->tqi_flags & AR5K_TXQ_FLAG_TXDESCINT_ENABLE)
00485                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_txdesc, queue);
00486 
00487                 if (tq->tqi_flags & AR5K_TXQ_FLAG_TXEOLINT_ENABLE)
00488                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_txeol, queue);
00489 
00490                 if (tq->tqi_flags & AR5K_TXQ_FLAG_CBRORNINT_ENABLE)
00491                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_cbrorn, queue);
00492 
00493                 if (tq->tqi_flags & AR5K_TXQ_FLAG_CBRURNINT_ENABLE)
00494                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_cbrurn, queue);
00495 
00496                 if (tq->tqi_flags & AR5K_TXQ_FLAG_QTRIGINT_ENABLE)
00497                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_qtrig, queue);
00498 
00499                 if (tq->tqi_flags & AR5K_TXQ_FLAG_TXNOFRMINT_ENABLE)
00500                         AR5K_Q_ENABLE_BITS(ah->ah_txq_imr_nofrm, queue);
00501 
00502                 /* Update secondary interrupt mask registers */
00503 
00504                 /* Filter out inactive queues */
00505                 ah->ah_txq_imr_txok &= ah->ah_txq_status;
00506                 ah->ah_txq_imr_txerr &= ah->ah_txq_status;
00507                 ah->ah_txq_imr_txurn &= ah->ah_txq_status;
00508                 ah->ah_txq_imr_txdesc &= ah->ah_txq_status;
00509                 ah->ah_txq_imr_txeol &= ah->ah_txq_status;
00510                 ah->ah_txq_imr_cbrorn &= ah->ah_txq_status;
00511                 ah->ah_txq_imr_cbrurn &= ah->ah_txq_status;
00512                 ah->ah_txq_imr_qtrig &= ah->ah_txq_status;
00513                 ah->ah_txq_imr_nofrm &= ah->ah_txq_status;
00514 
00515                 ath5k_hw_reg_write(ah, AR5K_REG_SM(ah->ah_txq_imr_txok,
00516                         AR5K_SIMR0_QCU_TXOK) |
00517                         AR5K_REG_SM(ah->ah_txq_imr_txdesc,
00518                         AR5K_SIMR0_QCU_TXDESC), AR5K_SIMR0);
00519                 ath5k_hw_reg_write(ah, AR5K_REG_SM(ah->ah_txq_imr_txerr,
00520                         AR5K_SIMR1_QCU_TXERR) |
00521                         AR5K_REG_SM(ah->ah_txq_imr_txeol,
00522                         AR5K_SIMR1_QCU_TXEOL), AR5K_SIMR1);
00523                 /* Update simr2 but don't overwrite rest simr2 settings */
00524                 AR5K_REG_DISABLE_BITS(ah, AR5K_SIMR2, AR5K_SIMR2_QCU_TXURN);
00525                 AR5K_REG_ENABLE_BITS(ah, AR5K_SIMR2,
00526                         AR5K_REG_SM(ah->ah_txq_imr_txurn,
00527                         AR5K_SIMR2_QCU_TXURN));
00528                 ath5k_hw_reg_write(ah, AR5K_REG_SM(ah->ah_txq_imr_cbrorn,
00529                         AR5K_SIMR3_QCBRORN) |
00530                         AR5K_REG_SM(ah->ah_txq_imr_cbrurn,
00531                         AR5K_SIMR3_QCBRURN), AR5K_SIMR3);
00532                 ath5k_hw_reg_write(ah, AR5K_REG_SM(ah->ah_txq_imr_qtrig,
00533                         AR5K_SIMR4_QTRIG), AR5K_SIMR4);
00534                 /* Set TXNOFRM_QCU for the queues with TXNOFRM enabled */
00535                 ath5k_hw_reg_write(ah, AR5K_REG_SM(ah->ah_txq_imr_nofrm,
00536                         AR5K_TXNOFRM_QCU), AR5K_TXNOFRM);
00537                 /* No queue has TXNOFRM enabled, disable the interrupt
00538                  * by setting AR5K_TXNOFRM to zero */
00539                 if (ah->ah_txq_imr_nofrm == 0)
00540                         ath5k_hw_reg_write(ah, 0, AR5K_TXNOFRM);
00541 
00542                 /* Set QCU mask for this DCU to save power */
00543                 AR5K_REG_WRITE_Q(ah, AR5K_QUEUE_QCUMASK(queue), queue);
00544         }
00545 
00546         return 0;
00547 }
00548 
00549 /*
00550  * Get slot time from DCU
00551  */
00552 unsigned int ath5k_hw_get_slot_time(struct ath5k_hw *ah)
00553 {
00554         ATH5K_TRACE(ah->ah_sc);
00555         if (ah->ah_version == AR5K_AR5210)
00556                 return ath5k_hw_clocktoh(ath5k_hw_reg_read(ah,
00557                                 AR5K_SLOT_TIME) & 0xffff, ah->ah_turbo);
00558         else
00559                 return ath5k_hw_reg_read(ah, AR5K_DCU_GBL_IFS_SLOT) & 0xffff;
00560 }
00561 
00562 /*
00563  * Set slot time on DCU
00564  */
00565 int ath5k_hw_set_slot_time(struct ath5k_hw *ah, unsigned int slot_time)
00566 {
00567         ATH5K_TRACE(ah->ah_sc);
00568         if (slot_time < AR5K_SLOT_TIME_9 || slot_time > AR5K_SLOT_TIME_MAX)
00569                 return -EINVAL;
00570 
00571         if (ah->ah_version == AR5K_AR5210)
00572                 ath5k_hw_reg_write(ah, ath5k_hw_htoclock(slot_time,
00573                                 ah->ah_turbo), AR5K_SLOT_TIME);
00574         else
00575                 ath5k_hw_reg_write(ah, slot_time, AR5K_DCU_GBL_IFS_SLOT);
00576 
00577         return 0;
00578 }
00579 


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