RT-WiFi v0.1

This commit is contained in:
Alexis Paques 2017-08-31 12:07:59 +02:00
parent 210da501c5
commit 8e721dd68a
21 changed files with 1181 additions and 67 deletions

11
.blacklist.map Normal file
View File

@ -0,0 +1,11 @@
# Update this map when a driver gets renamed or
# symbols from old drivers get moved to a newer
# driver. If you have the driver on the right
# hand side it will be blacklisted upon installation
# only if you actually installed the driver on the
# left.
# new-driver old-driver
iwlwifi iwlagn
iwl4965 iwlagn
videodev v4l2-compat-ioctl32

63
.gitignore vendored
View File

@ -1,52 +1,21 @@
# Prerequisites
*.d
*.*~
# Object files
Kconfig.kernel
Kconfig.versions
.kernel_config_md5
.config
.config.old
*~
*.o
*.d
.tmp_*
*.ko
*.obj
*.elf
# Linker output
*.ilk
*.map
*.exp
# Precompiled Headers
*.gch
*.pch
# Libraries
*.lib
*.a
*.la
*.lo
# Shared objects (inc. Windows DLLs)
*.dll
*.so
*.so.*
*.dylib
# Executables
*.exe
*.out
*.app
*.i*86
*.x86_64
*.hex
# Debug files
*.dSYM/
*.su
*.idb
*.pdb
# Kernel Module Compile Results
*.mod*
*.cmd
.tmp_versions/
*.tmp
*.ver
modules.order
backport-include/backport/autoconf.h
modules
kconf/mconf
kconf/conf
.tmp_versions
Module.symvers
Mkfile.old
dkms.conf
*.mod.c

View File

@ -142,6 +142,7 @@ ATH9K_TX99=
ATH9K_LEGACY_RATE_CONTROL=
ATH9K_RFKILL=
ATH9K_HTC=
RT_WIFI=
ATH9K_HTC_DEBUGFS=
CARL9170=
CARL9170_LEDS=

View File

@ -152,3 +152,10 @@ config ATH9K_HTC_DEBUGFS
depends on ATH9K_HTC && DEBUG_FS
---help---
Say Y, if you need access to ath9k_htc's statistics.
config RT_WIFI
bool "RT-WiFi support"
depends on ATH9K
default n
---help---
Say Y, if you want to support TDMA MAC for your ATH9k driver.

View File

@ -60,3 +60,5 @@ ath9k_htc-y += htc_hst.o \
ath9k_htc-$(CPTCFG_ATH9K_HTC_DEBUGFS) += htc_drv_debug.o
obj-$(CPTCFG_ATH9K_HTC) += ath9k_htc.o
ath9k-$(CPTCFG_RT_WIFI) += rt-wifi.o

View File

@ -15,6 +15,7 @@
*/
#include "hw.h"
#include "rt-wifi.h"
#include <linux/export.h>
#define AR_BufLen 0x00000fff

View File

@ -22,11 +22,15 @@
#include <linux/interrupt.h>
#include <linux/leds.h>
#include <linux/completion.h>
#include <linux/kfifo.h>
#include "debug.h"
#include "common.h"
#include "mci.h"
#include "dfs.h"
#ifdef CPTCFG_RT_WIFI
#include "rt-wifi.h"
#endif
/*
* Header for the ath9k.ko driver core *only* -- hw code nor any other driver
@ -113,8 +117,13 @@ int ath_descdma_setup(struct ath_softc *sc, struct ath_descdma *dd,
/* RX / TX */
/***********/
#define ATH_RXBUF 512
#define ATH_TXBUF 512
/* rt-wifi: Increase buffer size */
/*#define ATH_RXBUF 512
#define ATH_TXBUF 512 */
#define ATH_RXBUF 2048
#define ATH_TXBUF 2048
/* eom */
#define ATH_TXBUF_RESERVE 5
#define ATH_MAX_QDEPTH (ATH_TXBUF / 4 - ATH_TXBUF_RESERVE)
#define ATH_TXMAXTRY 13
@ -234,6 +243,9 @@ struct ath_buf {
dma_addr_t bf_buf_addr; /* physical addr of data buffer, for DMA */
struct ieee80211_tx_rate rates[4];
struct ath_buf_state bf_state;
#ifdef CPTCFG_RT_WIFI
u32 qnum;
#endif
};
struct ath_atx_tid {
@ -789,6 +801,34 @@ struct ath_softc {
atomic_t wow_sleep_proc_intr; /* in the middle of WoW sleep ? */
u32 wow_intr_before_sleep;
#endif
#ifdef CPTCFG_RT_WIFI
int rt_wifi_enable;
struct ath_gen_timer *rt_wifi_timer;
struct kfifo rt_wifi_fifo;
struct list_head rt_wifi_q;
spinlock_t rt_wifi_q_lock;
spinlock_t rt_wifi_fifo_lock;
int rt_wifi_qcount;
int rt_wifi_join;
int rt_wifi_slot_num;
int rt_wifi_slot_len; /* in micro sec */
u16 rt_wifi_superframe_size; /* in terms of time slot */
int rt_wifi_asn;
u64 rt_wifi_cur_tsf;
struct rt_wifi_sched *rt_wifi_superframe;
/* for AP only */
u64 rt_wifi_bc_tsf; /* broadcast tsf */
u64 rt_wifi_bc_asn; /* broadcast asn */
u64 rt_wifi_virt_start_tsf;
u32 rt_wifi_beacon_bfaddr;
u32 rt_wifi_beacon_bc;
#endif
};
#define SPECTRAL_SCAN_BITMASK 0x10

View File

@ -120,6 +120,9 @@ static struct ath_buf *ath9k_beacon_generate(struct ieee80211_hw *hw,
struct ieee80211_tx_info *info;
struct ieee80211_mgmt *mgmt_hdr;
int cabq_depth;
#ifdef CPTCFG_RT_WIFI
unsigned char *tmp, *src;
#endif
if (avp->av_bcbuf == NULL)
return NULL;
@ -138,6 +141,30 @@ static struct ath_buf *ath9k_beacon_generate(struct ieee80211_hw *hw,
if (skb == NULL)
return NULL;
#ifdef CPTCFG_RT_WIFI
/* Append TDMA information to a beacon frame by vendor specific info. */
if (sc->rt_wifi_enable == 1) {
sc->rt_wifi_bc_tsf += RT_WIFI_BEACON_INTVAL;
sc->rt_wifi_bc_asn +=
RT_WIFI_BEACON_INTVAL / sc->rt_wifi_slot_len;
tmp = skb_put(skb, RT_WIFI_BEACON_VEN_EXT_SIZE);
tmp[0] = RT_WIFI_BEACON_TAG; /* Tag number for Vendor Specific Info */
tmp[1] = 0x0F; /* Lengh of tag (exclude these two bytes) */
src = (unsigned char *)(&sc->rt_wifi_bc_asn);
memcpy((tmp+2), src, sizeof(int));
src = (unsigned char *)(&sc->rt_wifi_bc_tsf);
memcpy((tmp+6), src, sizeof(u64));
*(tmp+14) = RT_WIFI_TIME_SLOT_LEN;
src = (unsigned char *)(&sc->rt_wifi_superframe_size);
memcpy((tmp+15), src, sizeof(u16));
}
#endif
bf->bf_mpdu = skb;
mgmt_hdr = (struct ieee80211_mgmt *)skb->data;
@ -186,8 +213,13 @@ static struct ath_buf *ath9k_beacon_generate(struct ieee80211_hw *hw,
ath_draintxq(sc, cabq);
}
}
#ifdef CPTCFG_RT_WIFI
#define RT_WIFI_BEACON_SPEED_24MBPS 4
/* May change beacon data rate here. */
ath9k_beacon_setup(sc, vif, bf, RT_WIFI_BEACON_SPEED_24MBPS);
#else
ath9k_beacon_setup(sc, vif, bf, info->control.rates[0].idx);
#endif
if (skb)
ath_tx_cabq(hw, vif, skb);
@ -318,6 +350,7 @@ void ath9k_beacon_tasklet(unsigned long data)
bool edma = !!(ah->caps.hw_caps & ATH9K_HW_CAP_EDMA);
int slot;
if (test_bit(SC_OP_HW_RESET, &sc->sc_flags)) {
ath_dbg(common, RESET,
"reset work is pending, skip beaconing now\n");
@ -408,6 +441,12 @@ void ath9k_beacon_tasklet(unsigned long data)
/* NB: cabq traffic should already be queued and primed */
ath9k_hw_puttxbuf(ah, sc->beacon.beaconq, bf->bf_daddr);
#ifdef CPTCFG_RT_WIFI
REG_SET_BIT(ah, AR_DIAG_SW, AR_DIAG_FORCE_CH_IDLE_HIGH);
REG_SET_BIT(ah, AR_DIAG_SW, AR_DIAG_IGNORE_VIRT_CS);
REG_SET_BIT(ah, AR_D_GBL_IFS_MISC, AR_D_GBL_IFS_MISC_IGNORE_BACKOFF);
#endif
if (!edma)
ath9k_hw_txstart(ah, sc->beacon.beaconq);
}
@ -459,6 +498,16 @@ static void ath9k_beacon_config_ap(struct ath_softc *sc,
nexttbtt, intval, conf->beacon_interval);
ath9k_beacon_init(sc, nexttbtt, intval, true);
#ifdef CPTCFG_RT_WIFI
if(sc->rt_wifi_timer == NULL) {
RT_WIFI_DEBUG("No timer is allocated.\n");
} else {
RT_WIFI_DEBUG("AP timer starts.\n");
ath_rt_wifi_ap_start_timer(sc, intval, nexttbtt);
sc->rt_wifi_enable = 1;
}
#endif
}
/*

View File

@ -172,7 +172,8 @@ static void ath9k_gen_timer_start(struct ath_hw *ah,
}
}
static void ath9k_gen_timer_stop(struct ath_hw *ah, struct ath_gen_timer *timer)
/* rt-wifi static void ath9k_gen_timer_stop(struct ath_hw *ah, struct ath_gen_timer *timer) */
void ath9k_gen_timer_stop(struct ath_hw *ah, struct ath_gen_timer *timer)
{
struct ath_gen_timer_table *timer_table = &ah->hw_gen_timers;

View File

@ -3074,6 +3074,53 @@ void ath9k_hw_gen_timer_start(struct ath_hw *ah,
}
EXPORT_SYMBOL(ath9k_hw_gen_timer_start);
#ifdef CPTCFG_RT_WIFI
void ath9k_hw_gen_timer_start_absolute(struct ath_hw *ah,
struct ath_gen_timer *timer,
u32 trig_timeout,
u32 timer_period)
{
struct ath_gen_timer_table *timer_table = &ah->hw_gen_timers;
u32 timer_next;
BUG_ON(!timer_period);
set_bit(timer->index, &timer_table->timer_mask.timer_bits);
timer_next = trig_timeout;
/*
* Program generic timer registers
*/
REG_WRITE(ah, gen_tmr_configuration[timer->index].next_addr,
timer_next);
REG_WRITE(ah, gen_tmr_configuration[timer->index].period_addr,
timer_period);
REG_SET_BIT(ah, gen_tmr_configuration[timer->index].mode_addr,
gen_tmr_configuration[timer->index].mode_mask);
if (AR_SREV_9462(ah)) {
/*
* Starting from AR9462, each generic timer can select which tsf
* to use. But we still follow the old rule, 0 - 7 use tsf and
* 8 - 15 use tsf2.
*/
if ((timer->index < AR_GEN_TIMER_BANK_1_LEN))
REG_CLR_BIT(ah, AR_MAC_PCU_GEN_TIMER_TSF_SEL,
(1 << timer->index));
else
REG_SET_BIT(ah, AR_MAC_PCU_GEN_TIMER_TSF_SEL,
(1 << timer->index));
}
/* Enable both trigger and thresh interrupt masks */
REG_SET_BIT(ah, AR_IMR_S5,
(SM(AR_GENTMR_BIT(timer->index), AR_IMR_S5_GENTIMER_THRESH) |
SM(AR_GENTMR_BIT(timer->index), AR_IMR_S5_GENTIMER_TRIG)));
}
EXPORT_SYMBOL(ath9k_hw_gen_timer_start_absolute);
#endif
void ath9k_hw_gen_timer_stop(struct ath_hw *ah, struct ath_gen_timer *timer)
{
struct ath_gen_timer_table *timer_table = &ah->hw_gen_timers;

View File

@ -1089,6 +1089,11 @@ void ar9002_hw_load_ani_reg(struct ath_hw *ah, struct ath9k_channel *chan);
void ath9k_ani_reset(struct ath_hw *ah, bool is_scanning);
void ath9k_hw_ani_monitor(struct ath_hw *ah, struct ath9k_channel *chan);
void ath9k_hw_gen_timer_start_absolute(struct ath_hw *ah,
struct ath_gen_timer *timer,
u32 trig_timeout,
u32 timer_period);
#ifdef CPTCFG_ATH9K_BTCOEX_SUPPORT
static inline bool ath9k_hw_btcoex_is_enabled(struct ath_hw *ah)

View File

@ -661,6 +661,69 @@ static void ath9k_eeprom_release(struct ath_softc *sc)
release_firmware(sc->sc_ah->eeprom_blob);
}
#ifdef CPTCFG_RT_WIFI
static void test_trigger(void *arg)
{
printk(KERN_DEBUG "test trigger\n");
}
static void test_thres(void *arg)
{
printk(KERN_DEBUG "test thres\n");
}
static void ath9k_init_rt_wifi(struct ath_softc *sc)
{
int ret;
unsigned int fifo_size = sizeof(struct ath_buf*) * RT_WIFI_KFIFO_SIZE;
sc->rt_wifi_enable = 0;
ret = kfifo_alloc(&sc->rt_wifi_fifo, fifo_size, GFP_KERNEL);
if (ret != 0) {
printk(KERN_WARNING "%s: Error in allocating RT_WIFI FIFO %d.\n",
__FUNCTION__, ret);
}
INIT_LIST_HEAD(&(sc->rt_wifi_q));
sc->rt_wifi_qcount = 0;
spin_lock_init(&sc->rt_wifi_q_lock);
spin_lock_init(&sc->rt_wifi_fifo_lock);
sc->rt_wifi_timer = ath_gen_timer_alloc(sc->sc_ah, test_trigger, test_thres, (void*)sc, 7);
sc->rt_wifi_join = 0;
}
static void ath9k_deinit_rt_wifi(struct ath_softc *sc)
{
struct ath_buf *new_buf;
sc->rt_wifi_enable = 0;
/* TODO: Not sure if the deinit is handled properly. */
while (true) {
new_buf = ath_rt_wifi_get_buf_sta(sc);
if (new_buf != NULL) {
ath_rt_wifi_tx(sc, new_buf);
} else {
break;
}
}
while (!list_empty(&sc->rt_wifi_q)) {
new_buf = list_first_entry(&sc->rt_wifi_q, struct ath_buf, list);
list_del_init(&new_buf->list);
ath_rt_wifi_tx(sc, new_buf);
}
if (sc->rt_wifi_timer != NULL) {
ath9k_gen_timer_stop(sc->sc_ah, sc->rt_wifi_timer);
ath_gen_timer_free(sc->sc_ah, sc->rt_wifi_timer);
}
if (sc->rt_wifi_superframe != NULL) {
kfree(sc->rt_wifi_superframe);
}
}
#endif
static int ath9k_init_softc(u16 devid, struct ath_softc *sc,
const struct ath_bus_ops *bus_ops)
{
@ -766,9 +829,12 @@ static int ath9k_init_softc(u16 devid, struct ath_softc *sc,
if (ret)
goto err_queues;
/* rt-wifi: Disable Bluetooth co-existence for GENTIMER usage. */
#ifndef CPTCFG_RT_WIFI
ret = ath9k_init_btcoex(sc);
if (ret)
goto err_btcoex;
#endif
ret = ath9k_init_channels_rates(sc);
if (ret)
@ -778,6 +844,10 @@ static int ath9k_init_softc(u16 devid, struct ath_softc *sc,
ath9k_init_misc(sc);
ath_fill_led_pin(sc);
#ifdef CPTCFG_RT_WIFI
ath9k_init_rt_wifi(sc);
#endif
if (common->bus_ops->aspm_init)
common->bus_ops->aspm_init(common);
@ -1058,7 +1128,11 @@ static void ath9k_deinit_softc(struct ath_softc *sc)
{
int i = 0;
#ifdef CPTCFG_RT_WIFI
ath9k_deinit_rt_wifi(sc);
#else
ath9k_deinit_btcoex(sc);
#endif
for (i = 0; i < ATH9K_NUM_TX_QUEUES; i++)
if (ATH_TXQ_SETUP(sc, i))

View File

@ -489,8 +489,9 @@ void ath9k_tasklet(unsigned long data)
ath_tx_tasklet(sc);
}
#ifndef CPTCFG_RT_WIFI
ath9k_btcoex_handle_interrupt(sc, status);
#endif
/* re-enable hardware interrupt */
ath9k_hw_enable_interrupts(ah);
out:
@ -500,6 +501,7 @@ out:
irqreturn_t ath_isr(int irq, void *dev)
{
#ifndef CPTCFG_RT_WIFI
#define SCHED_INTR ( \
ATH9K_INT_FATAL | \
ATH9K_INT_BB_WATCHDOG | \
@ -512,8 +514,23 @@ irqreturn_t ath_isr(int irq, void *dev)
ATH9K_INT_BMISS | \
ATH9K_INT_CST | \
ATH9K_INT_TSFOOR | \
ATH9K_INT_GENTIMER | \
ATH9K_INT_GENTIMER| \
ATH9K_INT_MCI)
#else
#define SCHED_INTR ( \
ATH9K_INT_FATAL | \
ATH9K_INT_BB_WATCHDOG | \
ATH9K_INT_RXORN | \
ATH9K_INT_RXEOL | \
ATH9K_INT_RX | \
ATH9K_INT_RXLP | \
ATH9K_INT_RXHP | \
ATH9K_INT_TX | \
ATH9K_INT_BMISS | \
ATH9K_INT_CST | \
ATH9K_INT_TSFOOR | \
ATH9K_INT_MCI)
#endif
struct ath_softc *sc = dev;
struct ath_hw *ah = sc->sc_ah;
@ -530,7 +547,6 @@ irqreturn_t ath_isr(int irq, void *dev)
return IRQ_NONE;
/* shared irq, not for us */
if (!ath9k_hw_intrpend(ah))
return IRQ_NONE;
@ -548,6 +564,7 @@ irqreturn_t ath_isr(int irq, void *dev)
ath9k_hw_getisr(ah, &status); /* NB: clears ISR too */
status &= ah->imask; /* discard unasked-for bits */
/*
* If there are no status bits set, then this interrupt was not
* for me (should have been caught above).
@ -560,7 +577,6 @@ irqreturn_t ath_isr(int irq, void *dev)
if (status & SCHED_INTR)
sched = true;
/*
* If a FATAL or RXORN interrupt is received, we have to reset the
* chip immediately.
@ -599,12 +615,17 @@ irqreturn_t ath_isr(int irq, void *dev)
ath9k_hw_set_interrupts(ah);
}
#ifdef CPTCFG_RT_WIFI
if (status & ATH9K_INT_GENTIMER) {
ath9k_hw_disable_interrupts(ah);
ath_rt_wifi_tasklet(sc);
ath9k_hw_enable_interrupts(ah);
}
#endif
if (!(ah->caps.hw_caps & ATH9K_HW_CAP_AUTOSLEEP))
if (status & ATH9K_INT_TIM_TIMER) {
if (ATH_DBG_WARN_ON_ONCE(sc->ps_idle))
goto chip_reset;
/* Clear RxAbort bit so that we can
* receive frames */
ath9k_setpower(sc, ATH9K_PM_AWAKE);
spin_lock(&sc->sc_pm_lock);
ath9k_hw_setrxabort(sc->sc_ah, 0);
@ -808,6 +829,22 @@ static void ath9k_tx(struct ieee80211_hw *hw,
txctl.txq = sc->tx.txq_map[skb_get_queue_mapping(skb)];
txctl.sta = control->sta;
#ifdef CPTCFG_RT_WIFI
/* rt-wifi: Disable probe response. */
if (ieee80211_is_probe_resp(hdr->frame_control)) {
if(rt_wifi_authorized_sta(hdr->addr1) == false) {
RT_WIFI_DEBUG("Unauthorized destination address: %X:%X:%X:%X:%X:%X\n"
, hdr->addr1[0]
, hdr->addr1[1]
, hdr->addr1[2]
, hdr->addr1[3]
, hdr->addr1[4]
, hdr->addr1[5]);
goto exit;
}
}
#endif
ath_dbg(common, XMIT, "transmitting packet, skb: %p\n", skb);
if (ath_tx_start(hw, skb, &txctl) != 0) {
@ -1268,9 +1305,14 @@ static int ath9k_config(struct ieee80211_hw *hw, u32 changed)
sc->ps_idle = !!(conf->flags & IEEE80211_CONF_IDLE);
if (sc->ps_idle) {
ath_cancel_work(sc);
#ifndef CPTCFG_RT_WIFI
ath9k_stop_btcoex(sc);
#endif
} else {
#ifndef CPTCFG_RT_WIFI
ath9k_start_btcoex(sc);
#endif
/*
* The chip needs a reset to properly wake up from
* full sleep
@ -1454,6 +1496,14 @@ static int ath9k_conf_tx(struct ieee80211_hw *hw,
qi.tqi_cwmax = params->cw_max;
qi.tqi_burstTime = params->txop * 32;
#ifdef CPTCFG_RT_WIFI
#if RT_WIFI_ENABLE_COEX == 1
qi.tqi_aifs = 1;
qi.tqi_cwmin = 0;
qi.tqi_cwmax = 0;
#endif
#endif
ath_dbg(common, CONFIG,
"Configure tx [queue/halq] [%d/%d], aifs: %d, cw_min: %d, cw_max: %d, txop: %d\n",
queue, txq->axq_qnum, params->aifs, params->cw_min,
@ -2330,7 +2380,9 @@ static int ath9k_resume(struct ieee80211_hw *hw)
}
ath_restart_work(sc);
#ifndef CPTCFG_RT_WIFI
ath9k_start_btcoex(sc);
#endif
ath9k_ps_restore(sc);
mutex_unlock(&sc->mutex);

View File

@ -1417,8 +1417,9 @@ int ath_rx_tasklet(struct ath_softc *sc, int flush, bool hp)
else
bf = ath_get_next_rx_buf(sc, &rs);
if (!bf)
if (!bf) {
break;
}
skb = bf->bf_mpdu;
if (!skb)
@ -1441,6 +1442,7 @@ int ath_rx_tasklet(struct ath_softc *sc, int flush, bool hp)
if (retval)
goto requeue_drop_frag;
/* Ensure we always have an skb to requeue once we are done
* processing the current buffer's skb */
requeue_skb = ath_rxbuf_alloc(common, common->rx_bufsize, GFP_ATOMIC);
@ -1527,6 +1529,26 @@ int ath_rx_tasklet(struct ath_softc *sc, int flush, bool hp)
ath9k_apply_ampdu_details(sc, &rs, rxs);
#ifdef CPTCFG_RT_WIFI
if (rs.is_mybeacon) {
if ((ah->opmode == NL80211_IFTYPE_STATION)) {
if (sc->rt_wifi_enable == 0) {
ath_rt_wifi_rx_beacon(sc, skb);
} else {
u64 local_tsf = ath9k_hw_gettsf64(ah);
u64 cur_virt_tsf = sc->rt_wifi_virt_start_tsf + (sc->rt_wifi_asn * sc->rt_wifi_slot_len);
s64 diff = (cur_virt_tsf - local_tsf);
s64 k_ap_restart_diff_offset = 200000;
if (diff > k_ap_restart_diff_offset) {
RT_WIFI_DEBUG("Restart station timer, L: %llu, V: %llu\n", local_tsf, cur_virt_tsf);
ath9k_gen_timer_stop(sc->sc_ah, sc->rt_wifi_timer);
ath_rt_wifi_rx_beacon(sc, skb);
}
}
}
}
#endif
ieee80211_rx(hw, skb);
requeue_drop_frag:

View File

@ -0,0 +1,55 @@
/*
* Copyright (c) 2015, The University of Texas at Austin,
* Department of Computer Science, Cyberphysical Group
* http://www.cs.utexas.edu/~cps/ All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/* This is a configuration file for each RT-WiFi node.
* Copy this file to rt-wifi-local.h, and modify it accordingly before build
* RT-WiFi module */
#ifndef RT_WIFI_LOCAL_H
#define RT_WIFI_LOCAL_H
/* TDMA configuration */
/* TDMA slot size, see definition in rt-wifi.h */
#define RT_WIFI_TIME_SLOT_LEN 7
/* Transmission configuration */
/* co-existence */
#define RT_WIFI_ENABLE_COEX 0
/* # of in-slot transmission count */
#define RT_WIFI_NUM_OF_TRIES 1
/* Whether the sender will wait for ACK or not */
#define RT_WIFI_ENABLE_ACK 1
/* Debug or log information */
/* Uncomment the following flags to enable the corresponding logging.*/
/* Please note that logging may influence system performance. */
/* For low prioirty logging, please use trace_printk() instead. */
// #define RT_WIFI_DEBUG_ENABLE
// #define RT_WIFI_ALERT_ENABLE
#endif /* RT_WIFI_LOCAL_H */

View File

@ -0,0 +1,104 @@
/*
* Copyright (c) 2015, The University of Texas at Austin,
* Department of Computer Science, Cyberphysical Group
* http://www.cs.utexas.edu/~cps/ All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/* This is a configuration file for each RT-WiFi node.
* Copy this file to rt-wifi-sched.h, and modify it accordingly before build
* RT-WiFi module */
#ifndef RT_WIFI_SCHED_H
#define RT_WIFI_SCHED_H
#include "rt-wifi.h"
/* Authorized stations */
static struct rt_wifi_sta RT_WIFI_STAS[] = {
{ .mac_addr = {0x00, 0x22, 0x5F, 0xF6, 0x11, 0x21} }, // i7
{ .mac_addr = {0x00, 0x26, 0xB6, 0xF7, 0x72, 0x10} }, // i5
{ .mac_addr = {0x00, 0x22, 0x5F, 0xF6, 0x0E, 0xA7} }, // i3
{ .mac_addr = {0x00, 0x21, 0x63, 0xC9, 0x0C, 0xDB} } // Chr Box
};
static u16 RT_WIFI_STAS_NUM = ARRAY_SIZE(RT_WIFI_STAS);
/* Local ID of a station in the RT_WIFI_STAS array. For example, the local ID
* is 0x01 for i5 machine in the given RT_WIFI_STAS array. */
#define RT_WIFI_LOCAL_ID 0xFF
/* RT-WiFi TDMA schedule */
static struct rt_wifi_sched RT_WIFI_PRE_CONFIG_SCHED[] = {
{ .type = RT_WIFI_RX, 0, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 1, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 2, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 3, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 4, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 5, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 6, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 7, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 8, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 9, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 10, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 11, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 12, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 13, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 14, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 15, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 16, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 17, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 18, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 19, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 20, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 21, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 22, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 23, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 24, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 25, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 26, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 27, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 28, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 29, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 30, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 31, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 32, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 33, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 34, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 35, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 36, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 37, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 38, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 39, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 40, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 41, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 42, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 43, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 44, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 45, .sta_id = 0x00 },
{ .type = RT_WIFI_RX, 46, .sta_id = 0x00 },
{ .type = RT_WIFI_TX, 47, .sta_id = 0x00 },
{ .type = RT_WIFI_BEACON, 48},
{ .type = RT_WIFI_BEACON, 49},
};
#endif /* RT_WIFI_SCHED_H */

View File

@ -0,0 +1,437 @@
/*
* Copyright (c) 2015, The University of Texas at Austin,
* Department of Computer Science, Cyberphysical Group
* http://www.cs.utexas.edu/~cps/ All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include <linux/slab.h>
#include <linux/log2.h>
#include "ath9k.h"
#include "hw.h"
#include "rt-wifi-sched.h"
static struct ath_buf* ath_rt_wifi_get_buf_ap_tx(struct ath_softc *sc, u8 sta_id);
static struct ath_buf* ath_rt_wifi_get_buf_ap_shared(struct ath_softc *sc);
static u32 rt_wifi_get_slot_len(u8 time_slot)
{
if (time_slot == RT_WIFI_TIME_SLOT_64TU) {
return TU_TO_USEC(64);
} else if (time_slot == RT_WIFI_TIME_SLOT_32TU) {
return TU_TO_USEC(32);
} else if (time_slot == RT_WIFI_TIME_SLOT_16TU) {
return TU_TO_USEC(16);
} else if (time_slot == RT_WIFI_TIME_SLOT_4TU) {
return TU_TO_USEC(4);
} else if (time_slot == RT_WIFI_TIME_SLOT_2TU) {
return TU_TO_USEC(2);
} else if (time_slot == RT_WIFI_TIME_SLOT_1TU) {
return TU_TO_USEC(1);
} else if (time_slot == RT_WIFI_TIME_SLOT_512us) {
return 512;
} else if (time_slot == RT_WIFI_TIME_SLOT_256us) {
return 256;
} else {
RT_WIFI_ALERT("Unknown time slot!!!\n");
return 512;
}
}
static void rt_wifi_config_superframe(struct ath_softc *sc)
{
int idx;
sc->rt_wifi_superframe = kmalloc(
sizeof(struct rt_wifi_sched) * sc->rt_wifi_superframe_size,
GFP_ATOMIC);
if (!sc->rt_wifi_superframe) {
RT_WIFI_ALERT("Cannot get enough memory for superframe!!!\n");
return;
}
for (idx = 0; idx < sc->rt_wifi_superframe_size; ++idx) {
sc->rt_wifi_superframe[idx].type = RT_WIFI_SHARED;
}
for (idx = 0; idx < ARRAY_SIZE(RT_WIFI_PRE_CONFIG_SCHED); ++idx) {
if (RT_WIFI_PRE_CONFIG_SCHED[idx].offset < sc->rt_wifi_superframe_size) {
sc->rt_wifi_superframe[RT_WIFI_PRE_CONFIG_SCHED[idx].offset].type = RT_WIFI_PRE_CONFIG_SCHED[idx].type;
sc->rt_wifi_superframe[RT_WIFI_PRE_CONFIG_SCHED[idx].offset].sta_id = RT_WIFI_PRE_CONFIG_SCHED[idx].sta_id;
} else {
RT_WIFI_ALERT("Wrong pre-config scheudle index\n");
}
}
}
void ath_rt_wifi_ap_start_timer(struct ath_softc *sc, u32 bcon_intval, u32 nexttbtt)
{
struct ath_hw *ah;
u32 next_timer;
/* The new design align superframe with the init_beacon(), cur_tsf is 0 */
next_timer = nexttbtt - RT_WIFI_TIMER_OFFSET;
RT_WIFI_DEBUG("%s cur_tsf: %u, nexttbtt: %u, next_timer: %u\n", __FUNCTION__, 0, nexttbtt, next_timer);
sc->rt_wifi_slot_len = rt_wifi_get_slot_len(RT_WIFI_TIME_SLOT_LEN);
sc->rt_wifi_superframe_size = ARRAY_SIZE(RT_WIFI_PRE_CONFIG_SCHED);
RT_WIFI_DEBUG("time slot len: %u, superframe size: %u\n",
sc->rt_wifi_slot_len, sc->rt_wifi_superframe_size);
rt_wifi_config_superframe(sc);
ath9k_hw_gen_timer_start_absolute(sc->sc_ah, sc->rt_wifi_timer, next_timer, sc->rt_wifi_slot_len);
ah = sc->sc_ah;
if ((ah->imask & ATH9K_INT_GENTIMER) == 0) {
ath9k_hw_disable_interrupts(ah);
ah->imask |= ATH9K_INT_GENTIMER;
ath9k_hw_set_interrupts(ah);
ath9k_hw_enable_interrupts(ah);
}
sc->rt_wifi_virt_start_tsf = 0;
sc->rt_wifi_asn = (nexttbtt/sc->rt_wifi_slot_len) - 1;
sc->rt_wifi_bc_tsf = 0;
sc->rt_wifi_bc_asn = 0;
}
void ath_rt_wifi_sta_start_timer(struct ath_softc *sc)
{
struct ath_hw *ah;
u64 next_tsf;
u32 next_timer;
/* To compensate tsf drfit because of data rate of beacon frame */
sc->rt_wifi_virt_start_tsf = RT_WIFI_BEACON_DELAY_OFFSET;
/* start TDMA machine in the beginning of the next beacon */
next_tsf = sc->rt_wifi_cur_tsf + RT_WIFI_BEACON_INTVAL - RT_WIFI_TIMER_OFFSET + RT_WIFI_BEACON_DELAY_OFFSET;
next_timer = next_tsf & 0xffffffff;
ath9k_hw_gen_timer_start_absolute(sc->sc_ah, sc->rt_wifi_timer, next_timer, sc->rt_wifi_slot_len);
ah = sc->sc_ah;
if ((ah->imask & ATH9K_INT_GENTIMER) == 0) {
ath9k_hw_disable_interrupts(ah);
ah->imask |= ATH9K_INT_GENTIMER;
ath9k_hw_set_interrupts(ah);
ath9k_hw_enable_interrupts(ah);
}
sc->rt_wifi_asn = sc->rt_wifi_asn + (RT_WIFI_BEACON_INTVAL / sc->rt_wifi_slot_len) - 1;
RT_WIFI_DEBUG("%s cur_tsf: %llu, next_tsf: %llu, next_timer: %u, next_asn - 1: %d\n", __FUNCTION__, sc->rt_wifi_cur_tsf, next_tsf, next_timer, sc->rt_wifi_asn);
}
static struct ath_buf* ath_rt_wifi_get_buf_from_queue(struct ath_softc *sc, u8 sta_id)
{
struct ath_buf *bf_itr, *bf_tmp = NULL;
struct ieee80211_hdr *hdr;
spin_lock(&sc->rt_wifi_q_lock);
if (!list_empty(&sc->rt_wifi_q)) {
list_for_each_entry(bf_itr, &sc->rt_wifi_q, list) {
hdr = (struct ieee80211_hdr*)bf_itr->bf_mpdu->data;
if (rt_wifi_dst_sta(hdr->addr1, sta_id) == true) {
bf_tmp = bf_itr;
break;
}
}
if (bf_tmp != NULL) {
list_del_init(&bf_tmp->list);
}
}
spin_unlock(&sc->rt_wifi_q_lock);
return bf_tmp;
}
struct ath_buf* ath_rt_wifi_get_buf_sta(struct ath_softc *sc)
{
struct ath_buf *bf_tmp = NULL;
if (kfifo_len(&sc->rt_wifi_fifo) >= sizeof(struct ath_buf*)) {
kfifo_out(&sc->rt_wifi_fifo, &bf_tmp, sizeof(struct ath_buf*));
}
return bf_tmp;
}
struct ath_buf* ath_rt_wifi_get_buf_ap_tx(struct ath_softc *sc, u8 sta_id)
{
struct ath_buf *bf_itr, *bf_tmp = NULL;
struct ieee80211_hdr *hdr;
bf_tmp = ath_rt_wifi_get_buf_from_queue(sc, sta_id);
if (bf_tmp != NULL)
return bf_tmp;
while (kfifo_len(&sc->rt_wifi_fifo) >= sizeof(struct ath_buf*)) {
kfifo_out(&sc->rt_wifi_fifo, &bf_itr, sizeof(struct ath_buf*));
hdr = (struct ieee80211_hdr*)bf_itr->bf_mpdu->data;
if (rt_wifi_dst_sta(hdr->addr1, sta_id) == true) {
bf_tmp = bf_itr;
break;
} else {
spin_lock(&sc->rt_wifi_q_lock);
list_add_tail(&bf_itr->list, &sc->rt_wifi_q);
spin_unlock(&sc->rt_wifi_q_lock);
}
}
if (bf_tmp == NULL) {
bf_tmp = ath_rt_wifi_get_buf_ap_shared(sc);
}
return bf_tmp;
}
static struct ath_buf* ath_rt_wifi_get_buf_ap_shared(struct ath_softc *sc)
{
struct ath_buf *bf_tmp = NULL;
spin_lock(&sc->rt_wifi_q_lock);
if (!list_empty(&sc->rt_wifi_q)) {
bf_tmp = list_first_entry(&sc->rt_wifi_q, struct ath_buf, list);
list_del_init(&bf_tmp->list);
} else if (kfifo_len(&sc->rt_wifi_fifo) >= sizeof(struct ath_buf*)) {
kfifo_out(&sc->rt_wifi_fifo, &bf_tmp, sizeof(struct ath_buf*));
}
spin_unlock(&sc->rt_wifi_q_lock);
return bf_tmp;
}
void ath_rt_wifi_tx(struct ath_softc *sc, struct ath_buf *new_buf)
{
struct ath_hw *ah = sc->sc_ah;
struct ath_common *common = ath9k_hw_common(ah);
struct ath_buf *bf, *bf_last;
bool puttxbuf = false;
bool edma;
/* rt-wifi added */
bool internal = false;
struct ath_txq *txq;
struct list_head head_tmp, *head;
if(new_buf == NULL)
return;
REG_SET_BIT(ah, AR_DIAG_SW, AR_DIAG_RX_DIS | AR_DIAG_RX_ABORT);
/* mainpulate list to fit original dirver code. */
head = &head_tmp;
INIT_LIST_HEAD(head);
list_add_tail(&new_buf->list, head);
txq = &(sc->tx.txq[new_buf->qnum]);
/* original dirver code */
edma = !!(ah->caps.hw_caps & ATH9K_HW_CAP_EDMA);
bf = list_first_entry(head, struct ath_buf, list);
bf_last = list_entry(head->prev, struct ath_buf, list);
ath_dbg(common, QUEUE, "qnum: %d, txq depth: %d\n",
txq->axq_qnum, txq->axq_depth);
if (edma && list_empty(&txq->txq_fifo[txq->txq_headidx])) {
list_splice_tail_init(head, &txq->txq_fifo[txq->txq_headidx]);
INCR(txq->txq_headidx, ATH_TXFIFO_DEPTH);
puttxbuf = true;
}
else {
list_splice_tail_init(head, &txq->axq_q);
if (txq->axq_link) {
ath9k_hw_set_desc_link(ah, txq->axq_link, bf->bf_daddr);
ath_dbg(common, XMIT, "link[%u] (%p)=%llx (%p)\n",
txq->axq_qnum, txq->axq_link,
ito64(bf->bf_daddr), bf->bf_desc);
} else if (!edma)
puttxbuf = true;
txq->axq_link = bf_last->bf_desc;
}
if (puttxbuf) {
TX_STAT_INC(txq->axq_qnum, puttxbuf);
ath9k_hw_puttxbuf(ah, txq->axq_qnum, bf->bf_daddr);
ath_dbg(common, XMIT, "TXDP[%u] = %llx (%p)\n",
txq->axq_qnum, ito64(bf->bf_daddr), bf->bf_desc);
}
/* rt-wifi, disable carrier sense random backoff */
#if RT_WIFI_ENABLE_COEX == 0
REG_SET_BIT(ah, AR_DIAG_SW, AR_DIAG_FORCE_CH_IDLE_HIGH);
REG_SET_BIT(ah, AR_D_GBL_IFS_MISC, AR_D_GBL_IFS_MISC_IGNORE_BACKOFF);
#endif
REG_SET_BIT(ah, AR_DIAG_SW, AR_DIAG_IGNORE_VIRT_CS);
if (!edma || sc->tx99_state) {
TX_STAT_INC(txq->axq_qnum, txstart);
ath9k_hw_txstart(ah, txq->axq_qnum);
}
if (!internal) {
while (bf) {
txq->axq_depth++;
if (bf_is_ampdu_not_probing(bf))
txq->axq_ampdu_depth++;
bf_last = bf->bf_lastbf;
bf = bf_last->bf_next;
bf_last->bf_next = NULL;
}
}
REG_CLR_BIT(ah, AR_DIAG_SW, AR_DIAG_RX_DIS | AR_DIAG_RX_ABORT);
}
void ath_rt_wifi_tasklet(struct ath_softc *sc)
{
int sched_offset;
struct ath_buf *new_buf = NULL;
u64 cur_hw_tsf;
if (sc->rt_wifi_enable == 0) {
if (sc->sc_ah->opmode == NL80211_IFTYPE_AP) {
sc->rt_wifi_enable = 1;
} else {
RT_WIFI_DEBUG("RT_WIFI: not enable\n");
return;
}
}
/* House keeping */
sc->rt_wifi_asn++;
cur_hw_tsf = ath9k_hw_gettsf64(sc->sc_ah);
cur_hw_tsf = cur_hw_tsf - sc->rt_wifi_virt_start_tsf + (RT_WIFI_TIMER_OFFSET * 2);
sc->rt_wifi_asn = cur_hw_tsf >> ilog2((sc->rt_wifi_slot_len));
sched_offset = sc->rt_wifi_asn % sc->rt_wifi_superframe_size;
if (sc->sc_ah->opmode == NL80211_IFTYPE_AP) {
if (sc->rt_wifi_superframe[sched_offset].type == RT_WIFI_RX) {
RT_WIFI_DEBUG("RT_WIFI_RX(%d)\n", sched_offset);
new_buf = ath_rt_wifi_get_buf_ap_tx(sc,
sc->rt_wifi_superframe[sched_offset].sta_id);
} else if (sc->rt_wifi_superframe[sched_offset].type == RT_WIFI_SHARED) {
RT_WIFI_DEBUG("RT_WIFI_SHARED(%d)\n", sched_offset);
new_buf = ath_rt_wifi_get_buf_ap_shared(sc);
}
} else if (sc->sc_ah->opmode == NL80211_IFTYPE_STATION) {
if (sc->rt_wifi_superframe[sched_offset].type == RT_WIFI_TX
&& sc->rt_wifi_superframe[sched_offset].sta_id == RT_WIFI_LOCAL_ID) {
RT_WIFI_DEBUG("RT_WIFI_TX(%d)\n", sched_offset);
new_buf = ath_rt_wifi_get_buf_sta(sc);
}
}
ath_rt_wifi_tx(sc, new_buf);
}
bool rt_wifi_authorized_sta(u8 *addr) {
int i;
for (i = 0; i < RT_WIFI_STAS_NUM; i++) {
if ( addr[0]== RT_WIFI_STAS[i].mac_addr[0] &&
addr[1] == RT_WIFI_STAS[i].mac_addr[1] &&
addr[2] == RT_WIFI_STAS[i].mac_addr[2] &&
addr[3] == RT_WIFI_STAS[i].mac_addr[3] &&
addr[4] == RT_WIFI_STAS[i].mac_addr[4] &&
addr[5] == RT_WIFI_STAS[i].mac_addr[5] ) {
return true;
}
}
return false;
}
bool rt_wifi_dst_sta(u8 *addr, u8 sta_id) {
if (addr[0] == RT_WIFI_STAS[sta_id].mac_addr[0] &&
addr[1] == RT_WIFI_STAS[sta_id].mac_addr[1] &&
addr[2] == RT_WIFI_STAS[sta_id].mac_addr[2] &&
addr[3] == RT_WIFI_STAS[sta_id].mac_addr[3] &&
addr[4] == RT_WIFI_STAS[sta_id].mac_addr[4] &&
addr[5] == RT_WIFI_STAS[sta_id].mac_addr[5] ) {
return true;
}
return false;
}
void ath_rt_wifi_rx_beacon(struct ath_softc *sc, struct sk_buff *skb)
{
struct ath_hw *ah = sc->sc_ah;
unsigned char *data;
unsigned char slot_size;
u64 local_tsf;
__le16 stype;
struct ieee80211_mgmt *mgmt;
static u8 first_beacon = 1;
mgmt = (void*)skb->data;
stype = mgmt->frame_control & cpu_to_le16(IEEE80211_FCTL_STYPE);
data = (unsigned char*)skb->data;
data = data + skb->len - RT_WIFI_BEACON_VEN_EXT_SIZE - BEACON_FCS_SIZE;
if (*data != RT_WIFI_BEACON_TAG) {
RT_WIFI_ALERT("TAG mismatch %x\n", *data);
}
else {
// skip the first beacon for TSF synchronization
if (first_beacon == 1) {
first_beacon = 0;
return;
}
memcpy((unsigned char*)(&sc->rt_wifi_cur_tsf), (data+6), sizeof(u64));
RT_WIFI_DEBUG("beacon current tsf: %llu\n", sc->rt_wifi_cur_tsf);
local_tsf = ath9k_hw_gettsf64(ah);
if(local_tsf >= (sc->rt_wifi_cur_tsf - RT_WIFI_TSF_SYNC_OFFSET)) {
// Process beacon information
memcpy((unsigned char*)(&sc->rt_wifi_asn), (data+2), sizeof(int));
RT_WIFI_DEBUG("beacon asn: %u\n", sc->rt_wifi_asn);
memcpy(&slot_size, (data+14), sizeof(u8));
sc->rt_wifi_slot_len = rt_wifi_get_slot_len(slot_size);
RT_WIFI_DEBUG("slot len: %u\n", sc->rt_wifi_slot_len);
memcpy((unsigned char*)(&sc->rt_wifi_superframe_size), (data+15), sizeof(u16));
RT_WIFI_DEBUG("sf size: %u\n", sc->rt_wifi_superframe_size);
rt_wifi_config_superframe(sc);
ath_rt_wifi_sta_start_timer(sc);
sc->rt_wifi_enable = 1;
} else {
RT_WIFI_DEBUG("local_tsf: %llu < rt_wifi_cur_tsf: %llu - TSF_SYNC_OFFSET\n",
local_tsf, sc->rt_wifi_cur_tsf);
}
}
}

View File

@ -0,0 +1,110 @@
/*
* Copyright (c) 2015, The University of Texas at Austin,
* Department of Computer Science, Cyberphysical Group
* http://www.cs.utexas.edu/~cps/ All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef RT_WIFI_H
#define RT_WIFI_H
#include <linux/nl80211.h>
#include "ath9k.h"
#include "rt-wifi-local.h"
/* rt-wifi constant */
#define RT_WIFI_TIMER_OFFSET 50 /* compensate the isr invoking time */
#define RT_WIFI_TSF_SYNC_OFFSET 1000 /* max sync error in micro-sec */
#define RT_WIFI_BEACON_VEN_EXT_SIZE 17 // Size of vendor extension in beacon frame
#define BEACON_FCS_SIZE 4 // Size of frame check sequence in byte
#define RT_WIFI_BEACON_TAG 0xFE
#define RT_WIFI_BEACON_INTVAL 102400 /* in terms of microsec, default beacon time interval 100 time units
where 1TU = 1024 micro-sec */
#define RT_WIFI_BEACON_DELAY_OFFSET 60 /* in terms of micro-sec, this value is highly dependent on beacon data rate, 60us for 24Mbps */
#define RT_WIFI_KFIFO_SIZE 2048
// Make sure this # is the same as ath_tx_buf_size!!
// We do not take care of FIFO overflow.
#define RT_WIFI_TIME_SLOT_64TU 0
#define RT_WIFI_TIME_SLOT_32TU 1
#define RT_WIFI_TIME_SLOT_16TU 2
#define RT_WIFI_TIME_SLOT_8TU 3
#define RT_WIFI_TIME_SLOT_4TU 4
#define RT_WIFI_TIME_SLOT_2TU 5
#define RT_WIFI_TIME_SLOT_1TU 6
#define RT_WIFI_TIME_SLOT_512us 7
#define RT_WIFI_TIME_SLOT_256us 8
#define RT_WIFI_TIME_SLOT_128us 9
/* Macro for debugging */
#ifdef RT_WIFI_DEBUG_ENABLE
#define RT_WIFI_DEBUG(fmt, args...) printk(KERN_DEBUG "RT_WIFI: " fmt, ##args)
#else
#define RT_WIFI_DEBUG(fmt, args...)
#endif
/* Macro for alert message*/
#ifdef RT_WIFI_ALERT_ENABLE
#define RT_WIFI_ALERT(fmt, args...) printk(KERN_ALERT "RT_WIFI: " fmt, ##args)
#else
#define RT_WIFI_ALERT(fmt, args...)
#endif
struct rt_wifi_sta {
u8 mac_addr[ETH_ALEN];
};
/* link scheduling */
enum rt_wifi_link_type{
RT_WIFI_BEACON,
RT_WIFI_TX,
RT_WIFI_RX,
RT_WIFI_SHARED,
};
struct rt_wifi_sched{
enum rt_wifi_link_type type;
u16 offset;
u8 sta_id;
};
/* rt-wifi function prototype*/
void ath_rt_wifi_tasklet(struct ath_softc *sc);
void ath_rt_wifi_ap_start_timer(struct ath_softc *sc, u32 bcon_intval, u32 nexttbtt);
void ath_rt_wifi_sta_start_timer(struct ath_softc *sc);
void ath_rt_wifi_tx(struct ath_softc *sc, struct ath_buf *new_buf);
void ath_rt_wifi_rx_beacon(struct ath_softc *sc, struct sk_buff *skb);
struct ath_buf* ath_rt_wifi_get_buf_sta(struct ath_softc *sc);
bool rt_wifi_authorized_sta(u8 *addr);
inline bool rt_wifi_dst_sta(u8 *addr, u8 sta_id);
void ath9k_gen_timer_stop(struct ath_hw *ah, struct ath_gen_timer *timer);
/* existing functions not in rt-wifi*/
bool bf_is_ampdu_not_probing(struct ath_buf *bf);
/* other marco */
#define WLAN_GET_SEQ_SEQ(seq) (((seq) & IEEE80211_SCTL_SEQ) >> 4 )
#define WLAN_GET_SEQ_FRAG(seq) ((seq) & IEEE80211_SCTL_FRAG)
#endif /* RT_WIFI_H */

View File

@ -662,7 +662,8 @@ static void ath_tx_complete_aggr(struct ath_softc *sc, struct ath_txq *txq,
ath9k_queue_reset(sc, RESET_TYPE_TX_ERROR);
}
static bool bf_is_ampdu_not_probing(struct ath_buf *bf)
/* rt-wifi static bool bf_is_ampdu_not_probing(struct ath_buf *bf) */
bool bf_is_ampdu_not_probing(struct ath_buf *bf)
{
struct ieee80211_tx_info *info = IEEE80211_SKB_CB(bf->bf_mpdu);
return bf_isampdu(bf) && !(info->flags & IEEE80211_TX_CTL_RATE_CTRL_PROBE);
@ -1117,7 +1118,14 @@ static void ath_buf_set_rate(struct ath_softc *sc, struct ath_buf *bf,
continue;
rix = rates[i].idx;
#ifdef CPTCFG_RT_WIFI
if (i == 0)
info->rates[i].Tries = RT_WIFI_NUM_OF_TRIES;
else
info->rates[i].Tries = 0;
#else
info->rates[i].Tries = rates[i].count;
#endif
/*
* Handle RTS threshold for unaggregated HT frames.
@ -1167,6 +1175,7 @@ static void ath_buf_set_rate(struct ath_softc *sc, struct ath_buf *bf,
phy = WLAN_RC_PHY_OFDM;
info->rates[i].Rate = rate->hw_value;
if (rate->hw_value_short) {
if (rates[i].flags & IEEE80211_TX_RC_USE_SHORT_PREAMBLE)
info->rates[i].Rate |= rate->hw_value_short;
@ -1248,12 +1257,23 @@ static void ath_tx_fill_desc(struct ath_softc *sc, struct ath_buf *bf,
if (!sc->tx99_state)
info.flags = ATH9K_TXDESC_INTREQ;
#ifdef CPTCFG_RT_WIFI
/* rt-wifi: Clear destination mask for avoiding TXERR_FILT. */
info.flags |= ATH9K_TXDESC_CLRDMASK;
#if (RT_WIFI_ENABLE_ACK == 1)
if (tx_info->flags & IEEE80211_TX_CTL_NO_ACK)
info.flags |= ATH9K_TXDESC_NOACK;
#else
info.flags |= ATH9K_TXDESC_NOACK;
#endif
#else
if ((tx_info->flags & IEEE80211_TX_CTL_CLEAR_PS_FILT) ||
txq == sc->tx.uapsdq)
info.flags |= ATH9K_TXDESC_CLRDMASK;
if (tx_info->flags & IEEE80211_TX_CTL_NO_ACK)
info.flags |= ATH9K_TXDESC_NOACK;
#endif
if (tx_info->flags & IEEE80211_TX_CTL_LDPC)
info.flags |= ATH9K_TXDESC_LDPC;
@ -1902,10 +1922,9 @@ static void ath_tx_txqaddbuf(struct ath_softc *sc, struct ath_txq *txq,
{
struct ath_hw *ah = sc->sc_ah;
struct ath_common *common = ath9k_hw_common(ah);
struct ath_buf *bf, *bf_last;
struct ath_buf *bf, *bf_last, *bf_itr;
bool puttxbuf = false;
bool edma;
/*
* Insert the frame on the outbound list and
* pass it on to the hardware.
@ -1914,12 +1933,13 @@ static void ath_tx_txqaddbuf(struct ath_softc *sc, struct ath_txq *txq,
if (list_empty(head))
return;
#ifndef CPTCFG_RT_WIFI
edma = !!(ah->caps.hw_caps & ATH9K_HW_CAP_EDMA);
bf = list_first_entry(head, struct ath_buf, list);
bf_last = list_entry(head->prev, struct ath_buf, list);
ath_dbg(common, QUEUE, "qnum: %d, txq depth: %d\n",
txq->axq_qnum, txq->axq_depth);
txq->axq_qnum, txq->axq_depth);
if (edma && list_empty(&txq->txq_fifo[txq->txq_headidx])) {
list_splice_tail_init(head, &txq->txq_fifo[txq->txq_headidx]);
@ -1931,8 +1951,8 @@ static void ath_tx_txqaddbuf(struct ath_softc *sc, struct ath_txq *txq,
if (txq->axq_link) {
ath9k_hw_set_desc_link(ah, txq->axq_link, bf->bf_daddr);
ath_dbg(common, XMIT, "link[%u] (%p)=%llx (%p)\n",
txq->axq_qnum, txq->axq_link,
ito64(bf->bf_daddr), bf->bf_desc);
txq->axq_qnum, txq->axq_link,
ito64(bf->bf_daddr), bf->bf_desc);
} else if (!edma)
puttxbuf = true;
@ -1943,7 +1963,7 @@ static void ath_tx_txqaddbuf(struct ath_softc *sc, struct ath_txq *txq,
TX_STAT_INC(txq->axq_qnum, puttxbuf);
ath9k_hw_puttxbuf(ah, txq->axq_qnum, bf->bf_daddr);
ath_dbg(common, XMIT, "TXDP[%u] = %llx (%p)\n",
txq->axq_qnum, ito64(bf->bf_daddr), bf->bf_desc);
txq->axq_qnum, ito64(bf->bf_daddr), bf->bf_desc);
}
if (!edma || sc->tx99_state) {
@ -1962,6 +1982,74 @@ static void ath_tx_txqaddbuf(struct ath_softc *sc, struct ath_txq *txq,
bf_last->bf_next = NULL;
}
}
#else
if (sc->rt_wifi_enable == 0) {
edma = !!(ah->caps.hw_caps & ATH9K_HW_CAP_EDMA);
bf = list_first_entry(head, struct ath_buf, list);
bf_last = list_entry(head->prev, struct ath_buf, list);
ath_dbg(common, QUEUE, "qnum: %d, txq depth: %d\n",
txq->axq_qnum, txq->axq_depth);
if (edma && list_empty(&txq->txq_fifo[txq->txq_headidx])) {
list_splice_tail_init(head, &txq->txq_fifo[txq->txq_headidx]);
INCR(txq->txq_headidx, ATH_TXFIFO_DEPTH);
puttxbuf = true;
} else {
list_splice_tail_init(head, &txq->axq_q);
if (txq->axq_link) {
ath9k_hw_set_desc_link(ah, txq->axq_link, bf->bf_daddr);
ath_dbg(common, XMIT, "link[%u] (%p)=%llx (%p)\n",
txq->axq_qnum, txq->axq_link,
ito64(bf->bf_daddr), bf->bf_desc);
} else if (!edma)
puttxbuf = true;
txq->axq_link = bf_last->bf_desc;
}
if (puttxbuf) {
TX_STAT_INC(txq->axq_qnum, puttxbuf);
ath9k_hw_puttxbuf(ah, txq->axq_qnum, bf->bf_daddr);
ath_dbg(common, XMIT, "TXDP[%u] = %llx (%p)\n",
txq->axq_qnum, ito64(bf->bf_daddr), bf->bf_desc);
}
if (!edma || sc->tx99_state) {
TX_STAT_INC(txq->axq_qnum, txstart);
ath9k_hw_txstart(ah, txq->axq_qnum);
}
if (!internal) {
while (bf) {
txq->axq_depth++;
if (bf_is_ampdu_not_probing(bf))
txq->axq_ampdu_depth++;
bf_last = bf->bf_lastbf;
bf = bf_last->bf_next;
bf_last->bf_next = NULL;
}
}
} else if (sc->rt_wifi_enable == 1) {
unsigned long flags;
spin_lock_irqsave(&sc->rt_wifi_fifo_lock, flags);
list_for_each_entry(bf_itr, head, list) {
if (kfifo_avail(&sc->rt_wifi_fifo) >=
sizeof(struct ath_buf*)) {
kfifo_in(&sc->rt_wifi_fifo,
&bf_itr,
sizeof(struct ath_buf*));
} else {
RT_WIFI_DEBUG(
"KFIFO is out of space!! If this"
"happens, investigate RT_WIFI_KFIFO_SIZE\n");
}
}
spin_unlock_irqrestore(&sc->rt_wifi_fifo_lock, flags);
}
#endif
}
static void ath_tx_send_normal(struct ath_softc *sc, struct ath_txq *txq,
@ -1972,6 +2060,19 @@ static void ath_tx_send_normal(struct ath_softc *sc, struct ath_txq *txq,
struct list_head bf_head;
struct ath_buf *bf = fi->bf;
/* rt-wifi */
struct ieee80211_hdr *hdr;
hdr = (struct ieee80211_hdr*)skb->data;
RT_WIFI_DEBUG( "New destination address: %X:%X:%X:%X:%X:%X\n"
, hdr->addr1[0]
, hdr->addr1[1]
, hdr->addr1[2]
, hdr->addr1[3]
, hdr->addr1[4]
, hdr->addr1[5]);
/* eom */
INIT_LIST_HEAD(&bf_head);
list_add_tail(&bf->list, &bf_head);
bf->bf_state.bf_type = 0;
@ -2072,6 +2173,10 @@ static struct ath_buf *ath_tx_setup_buffer(struct ath_softc *sc,
ATH_TXBUF_RESET(bf);
#ifdef CPTCFG_RT_WIFI
bf->qnum = txq->axq_qnum;
#endif
if (tid) {
fragno = le16_to_cpu(hdr->seq_ctrl) & IEEE80211_SCTL_FRAG;
seqno = tid->seq_next;

View File

@ -13,7 +13,9 @@
* ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
* OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
*/
/* rt-wifi */
#define ATH_USER_REGD 1
/* eom */
#define pr_fmt(fmt) KBUILD_MODNAME ": " fmt
#include <linux/kernel.h>
@ -196,6 +198,9 @@ ath_reg_apply_beaconing_flags(struct wiphy *wiphy,
struct ieee80211_channel *ch;
unsigned int i;
#ifdef ATH_USER_REGD
return;
#endif
for (band = 0; band < IEEE80211_NUM_BANDS; band++) {
if (!wiphy->bands[band])
@ -250,6 +255,9 @@ ath_reg_apply_active_scan_flags(struct wiphy *wiphy,
struct ieee80211_channel *ch;
const struct ieee80211_reg_rule *reg_rule;
#ifdef ATH_USER_REGD
return;
#endif
sband = wiphy->bands[IEEE80211_BAND_2GHZ];
if (!sband)
return;
@ -299,6 +307,10 @@ static void ath_reg_apply_radar_flags(struct wiphy *wiphy)
struct ieee80211_channel *ch;
unsigned int i;
#ifdef ATH_USER_REGD
return;
#endif
if (!wiphy->bands[IEEE80211_BAND_5GHZ])
return;
@ -607,6 +619,9 @@ ath_regd_init_wiphy(struct ath_regulatory *reg,
struct regulatory_request *request))
{
const struct ieee80211_regdomain *regd;
#ifdef ATH_USER_REGD
return;
#endif
wiphy->reg_notifier = reg_notifier;
wiphy->flags |= WIPHY_FLAG_STRICT_REGULATORY;

View File

@ -819,6 +819,10 @@ void ieee80211_send_nullfunc(struct ieee80211_local *local,
struct ieee80211_hdr_3addr *nullfunc;
struct ieee80211_if_managed *ifmgd = &sdata->u.mgd;
/* rt-wifi: Debug */
printk(KERN_DEBUG "RT_WIFI: %s\n", __FUNCTION__);
/* eom */
skb = ieee80211_nullfunc_get(&local->hw, &sdata->vif);
if (!skb)
return;
@ -1842,7 +1846,10 @@ static void ieee80211_mgd_probe_ap_send(struct ieee80211_sub_if_data *sdata)
if (sdata->local->hw.flags & IEEE80211_HW_REPORTS_TX_ACK_STATUS) {
ifmgd->nullfunc_failed = false;
ieee80211_send_nullfunc(sdata->local, sdata, 0);
/* rt-wifi: Disable Null data frame. */
/* TODO: Should verify this is worth to do in the new driver */
/* ieee80211_send_nullfunc(sdata->local, sdata, 0); */
/* eom */
} else {
int ssid_len;