linux-wireless.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH 1/4] ath9k_hw: store the clock rate in common data on channel changes
@ 2010-10-08 20:13 Felix Fietkau
  2010-10-08 20:13 ` [PATCH 2/4] ath5k: " Felix Fietkau
  0 siblings, 1 reply; 5+ messages in thread
From: Felix Fietkau @ 2010-10-08 20:13 UTC (permalink / raw)
  To: linux-wireless; +Cc: linville, lrodriguez, br1

Signed-off-by: Felix Fietkau <nbd@openwrt.org>
---
 drivers/net/wireless/ath/ath.h       |    2 ++
 drivers/net/wireless/ath/ath9k/ani.c |   26 ++------------------------
 drivers/net/wireless/ath/ath9k/hw.c  |   32 +++++++++++++++++++-------------
 3 files changed, 23 insertions(+), 37 deletions(-)

diff --git a/drivers/net/wireless/ath/ath.h b/drivers/net/wireless/ath/ath.h
index cee0191..b36d9d7 100644
--- a/drivers/net/wireless/ath/ath.h
+++ b/drivers/net/wireless/ath/ath.h
@@ -145,6 +145,8 @@ struct ath_common {
 	DECLARE_BITMAP(tkip_keymap, ATH_KEYMAX);
 	enum ath_crypt_caps crypt_caps;
 
+	unsigned int clockrate;
+
 	struct ath_regulatory regulatory;
 	const struct ath_ops *ops;
 	const struct ath_bus_ops *bus_ops;
diff --git a/drivers/net/wireless/ath/ath9k/ani.c b/drivers/net/wireless/ath/ath9k/ani.c
index f2a907b..f2aa684 100644
--- a/drivers/net/wireless/ath/ath9k/ani.c
+++ b/drivers/net/wireless/ath/ath9k/ani.c
@@ -465,35 +465,13 @@ static void ath9k_hw_ani_lower_immunity(struct ath_hw *ah)
 		ath9k_hw_set_cck_nil(ah, aniState->cckNoiseImmunityLevel - 1);
 }
 
-static u8 ath9k_hw_chan_2_clockrate_mhz(struct ath_hw *ah)
-{
-	struct ath9k_channel *chan = ah->curchan;
-	struct ieee80211_conf *conf = &ath9k_hw_common(ah)->hw->conf;
-	u8 clockrate; /* in MHz */
-
-	if (!ah->curchan) /* should really check for CCK instead */
-		clockrate = ATH9K_CLOCK_RATE_CCK;
-	else if (conf->channel->band == IEEE80211_BAND_2GHZ)
-		clockrate = ATH9K_CLOCK_RATE_2GHZ_OFDM;
-	else if (IS_CHAN_A_FAST_CLOCK(ah, chan))
-		clockrate = ATH9K_CLOCK_FAST_RATE_5GHZ_OFDM;
-	else
-		clockrate = ATH9K_CLOCK_RATE_5GHZ_OFDM;
-
-	if (conf_is_ht40(conf))
-		return clockrate * 2;
-
-	return clockrate;
-}
-
 static int32_t ath9k_hw_ani_get_listen_time(struct ath_hw *ah)
 {
+	struct ath_common *common = ath9k_hw_common(ah);
 	int32_t listen_time;
-	int32_t clock_rate;
 
 	ath9k_hw_update_cycle_counters(ah);
-	clock_rate = ath9k_hw_chan_2_clockrate_mhz(ah) * 1000;
-	listen_time = ah->listen_time / clock_rate;
+	listen_time = ah->listen_time / (common->clockrate * 1000);
 	ah->listen_time = 0;
 
 	return listen_time;
diff --git a/drivers/net/wireless/ath/ath9k/hw.c b/drivers/net/wireless/ath/ath9k/hw.c
index 05e9935..f5d7917 100644
--- a/drivers/net/wireless/ath/ath9k/hw.c
+++ b/drivers/net/wireless/ath/ath9k/hw.c
@@ -88,29 +88,32 @@ static void ath9k_hw_ani_cache_ini_regs(struct ath_hw *ah)
 /* Helper Functions */
 /********************/
 
-static u32 ath9k_hw_mac_clks(struct ath_hw *ah, u32 usecs)
+static void ath9k_hw_set_clockrate(struct ath_hw *ah)
 {
 	struct ieee80211_conf *conf = &ath9k_hw_common(ah)->hw->conf;
+	struct ath_common *common = ath9k_hw_common(ah);
+	unsigned int clockrate;
 
 	if (!ah->curchan) /* should really check for CCK instead */
-		return usecs *ATH9K_CLOCK_RATE_CCK;
-	if (conf->channel->band == IEEE80211_BAND_2GHZ)
-		return usecs *ATH9K_CLOCK_RATE_2GHZ_OFDM;
-
-	if (ah->caps.hw_caps & ATH9K_HW_CAP_FASTCLOCK)
-		return usecs * ATH9K_CLOCK_FAST_RATE_5GHZ_OFDM;
+		clockrate = ATH9K_CLOCK_RATE_CCK;
+	else if (conf->channel->band == IEEE80211_BAND_2GHZ)
+		clockrate = ATH9K_CLOCK_RATE_2GHZ_OFDM;
+	else if (ah->caps.hw_caps & ATH9K_HW_CAP_FASTCLOCK)
+		clockrate = ATH9K_CLOCK_FAST_RATE_5GHZ_OFDM;
 	else
-		return usecs * ATH9K_CLOCK_RATE_5GHZ_OFDM;
+		clockrate = ATH9K_CLOCK_RATE_5GHZ_OFDM;
+
+	if (conf_is_ht40(conf))
+		clockrate *= 2;
+
+	common->clockrate = clockrate;
 }
 
 static u32 ath9k_hw_mac_to_clks(struct ath_hw *ah, u32 usecs)
 {
-	struct ieee80211_conf *conf = &ath9k_hw_common(ah)->hw->conf;
+	struct ath_common *common = ath9k_hw_common(ah);
 
-	if (conf_is_ht40(conf))
-		return ath9k_hw_mac_clks(ah, usecs) * 2;
-	else
-		return ath9k_hw_mac_clks(ah, usecs);
+	return usecs * common->clockrate;
 }
 
 bool ath9k_hw_wait(struct ath_hw *ah, u32 reg, u32 mask, u32 val, u32 timeout)
@@ -1156,6 +1159,7 @@ static bool ath9k_hw_channel_change(struct ath_hw *ah,
 			  "Failed to set channel\n");
 		return false;
 	}
+	ath9k_hw_set_clockrate(ah);
 
 	ah->eep_ops->set_txpower(ah, chan,
 			     ath9k_regd_get_ctl(regulatory, chan),
@@ -1368,6 +1372,8 @@ int ath9k_hw_reset(struct ath_hw *ah, struct ath9k_channel *chan,
 	if (r)
 		return r;
 
+	ath9k_hw_set_clockrate(ah);
+
 	ENABLE_REGWRITE_BUFFER(ah);
 
 	for (i = 0; i < AR_NUM_DCU; i++)
-- 
1.7.2.2


^ permalink raw reply related	[flat|nested] 5+ messages in thread

* [PATCH 2/4] ath5k: store the clock rate in common data on channel changes
  2010-10-08 20:13 [PATCH 1/4] ath9k_hw: store the clock rate in common data on channel changes Felix Fietkau
@ 2010-10-08 20:13 ` Felix Fietkau
  2010-10-08 20:13   ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Felix Fietkau
  0 siblings, 1 reply; 5+ messages in thread
From: Felix Fietkau @ 2010-10-08 20:13 UTC (permalink / raw)
  To: linux-wireless; +Cc: linville, lrodriguez, br1

Signed-off-by: Felix Fietkau <nbd@openwrt.org>
---
 drivers/net/wireless/ath/ath5k/ath5k.h |    2 +-
 drivers/net/wireless/ath/ath5k/pcu.c   |   13 ++++++++-----
 drivers/net/wireless/ath/ath5k/phy.c   |    1 +
 3 files changed, 10 insertions(+), 6 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/ath5k.h b/drivers/net/wireless/ath/ath5k/ath5k.h
index 0cba2e3..4a367cd 100644
--- a/drivers/net/wireless/ath/ath5k/ath5k.h
+++ b/drivers/net/wireless/ath/ath5k/ath5k.h
@@ -1201,7 +1201,7 @@ void ath5k_hw_set_ack_bitrate_high(struct ath5k_hw *ah, bool high);
 /* Clock rate related functions */
 unsigned int ath5k_hw_htoclock(struct ath5k_hw *ah, unsigned int usec);
 unsigned int ath5k_hw_clocktoh(struct ath5k_hw *ah, unsigned int clock);
-unsigned int ath5k_hw_get_clockrate(struct ath5k_hw *ah);
+void ath5k_hw_set_clockrate(struct ath5k_hw *ah);
 
 /* Queue Control Unit, DFS Control Unit Functions */
 int ath5k_hw_get_tx_queueprops(struct ath5k_hw *ah, int queue,
diff --git a/drivers/net/wireless/ath/ath5k/pcu.c b/drivers/net/wireless/ath/ath5k/pcu.c
index 095d30b..074b4c6 100644
--- a/drivers/net/wireless/ath/ath5k/pcu.c
+++ b/drivers/net/wireless/ath/ath5k/pcu.c
@@ -207,7 +207,8 @@ static int ath5k_hw_set_cts_timeout(struct ath5k_hw *ah, unsigned int timeout)
  */
 unsigned int ath5k_hw_htoclock(struct ath5k_hw *ah, unsigned int usec)
 {
-	return usec * ath5k_hw_get_clockrate(ah);
+	struct ath_common *common = ath5k_hw_common(ah);
+	return usec * common->clockrate;
 }
 
 /**
@@ -216,17 +217,19 @@ unsigned int ath5k_hw_htoclock(struct ath5k_hw *ah, unsigned int usec)
  */
 unsigned int ath5k_hw_clocktoh(struct ath5k_hw *ah, unsigned int clock)
 {
-	return clock / ath5k_hw_get_clockrate(ah);
+	struct ath_common *common = ath5k_hw_common(ah);
+	return clock / common->clockrate;
 }
 
 /**
- * ath5k_hw_get_clockrate - Get the clock rate for current mode
+ * ath5k_hw_set_clockrate - Set common->clockrate for the current channel
  *
  * @ah: The &struct ath5k_hw
  */
-unsigned int ath5k_hw_get_clockrate(struct ath5k_hw *ah)
+void ath5k_hw_set_clockrate(struct ath5k_hw *ah)
 {
 	struct ieee80211_channel *channel = ah->ah_current_channel;
+	struct ath_common *common = ath5k_hw_common(ah);
 	int clock;
 
 	if (channel->hw_value & CHANNEL_5GHZ)
@@ -240,7 +243,7 @@ unsigned int ath5k_hw_get_clockrate(struct ath5k_hw *ah)
 	if (channel->hw_value & CHANNEL_TURBO)
 		clock *= 2;
 
-	return clock;
+	common->clockrate = clock;
 }
 
 /**
diff --git a/drivers/net/wireless/ath/ath5k/phy.c b/drivers/net/wireless/ath/ath5k/phy.c
index 61da913..2193678 100644
--- a/drivers/net/wireless/ath/ath5k/phy.c
+++ b/drivers/net/wireless/ath/ath5k/phy.c
@@ -1093,6 +1093,7 @@ int ath5k_hw_channel(struct ath5k_hw *ah, struct ieee80211_channel *channel)
 
 	ah->ah_current_channel = channel;
 	ah->ah_turbo = channel->hw_value == CHANNEL_T ? true : false;
+	ath5k_hw_set_clockrate(ah);
 
 	return 0;
 }
-- 
1.7.2.2


^ permalink raw reply related	[flat|nested] 5+ messages in thread

* [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath
  2010-10-08 20:13 ` [PATCH 2/4] ath5k: " Felix Fietkau
@ 2010-10-08 20:13   ` Felix Fietkau
  2010-10-08 20:13     ` [PATCH 4/4] ath5k: use the common cycle counter / listen time implementation Felix Fietkau
  2010-10-15 21:40     ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Ben Greear
  0 siblings, 2 replies; 5+ messages in thread
From: Felix Fietkau @ 2010-10-08 20:13 UTC (permalink / raw)
  To: linux-wireless; +Cc: linville, lrodriguez, br1

Instead of keeping track of wraparound, clear the counters on every
access and keep separate deltas for ANI and later survey use.
Also moves the function for calculating the 'listen time' for ANI

Signed-off-by: Felix Fietkau <nbd@openwrt.org>
Signed-off-by: Bruno Randolf <br1@einfach.org>
---
 drivers/net/wireless/ath/ath.h              |   14 ++++++
 drivers/net/wireless/ath/ath9k/ani.c        |   64 +-------------------------
 drivers/net/wireless/ath/ath9k/ani.h        |    8 ---
 drivers/net/wireless/ath/ath9k/ar9003_phy.c |    7 +--
 drivers/net/wireless/ath/ath9k/hw.h         |    2 -
 drivers/net/wireless/ath/ath9k/main.c       |   12 +++++-
 drivers/net/wireless/ath/ath9k/reg.h        |   11 -----
 drivers/net/wireless/ath/hw.c               |   59 ++++++++++++++++++++++++
 drivers/net/wireless/ath/reg.h              |   11 +++++
 9 files changed, 101 insertions(+), 87 deletions(-)

diff --git a/drivers/net/wireless/ath/ath.h b/drivers/net/wireless/ath/ath.h
index b36d9d7..501050c 100644
--- a/drivers/net/wireless/ath/ath.h
+++ b/drivers/net/wireless/ath/ath.h
@@ -19,6 +19,7 @@
 
 #include <linux/skbuff.h>
 #include <linux/if_ether.h>
+#include <linux/spinlock.h>
 #include <net/mac80211.h>
 
 /*
@@ -42,6 +43,13 @@ struct ath_ani {
 	struct timer_list timer;
 };
 
+struct ath_cycle_counters {
+	u32 cycles;
+	u32 rx_busy;
+	u32 rx_frame;
+	u32 tx_frame;
+};
+
 enum ath_device_state {
 	ATH_HW_UNAVAILABLE,
 	ATH_HW_INITIALIZED,
@@ -147,6 +155,10 @@ struct ath_common {
 
 	unsigned int clockrate;
 
+	spinlock_t cc_lock;
+	struct ath_cycle_counters cc_ani;
+	struct ath_cycle_counters cc_survey;
+
 	struct ath_regulatory regulatory;
 	const struct ath_ops *ops;
 	const struct ath_bus_ops *bus_ops;
@@ -163,5 +175,7 @@ int ath_key_config(struct ath_common *common,
 			  struct ieee80211_sta *sta,
 			  struct ieee80211_key_conf *key);
 bool ath_hw_keyreset(struct ath_common *common, u16 entry);
+void ath_hw_cycle_counters_update(struct ath_common *common);
+int32_t ath_hw_get_listen_time(struct ath_common *common);
 
 #endif /* ATH_H */
diff --git a/drivers/net/wireless/ath/ath9k/ani.c b/drivers/net/wireless/ath/ath9k/ani.c
index f2aa684..3aa8fb1 100644
--- a/drivers/net/wireless/ath/ath9k/ani.c
+++ b/drivers/net/wireless/ath/ath9k/ani.c
@@ -465,18 +465,6 @@ static void ath9k_hw_ani_lower_immunity(struct ath_hw *ah)
 		ath9k_hw_set_cck_nil(ah, aniState->cckNoiseImmunityLevel - 1);
 }
 
-static int32_t ath9k_hw_ani_get_listen_time(struct ath_hw *ah)
-{
-	struct ath_common *common = ath9k_hw_common(ah);
-	int32_t listen_time;
-
-	ath9k_hw_update_cycle_counters(ah);
-	listen_time = ah->listen_time / (common->clockrate * 1000);
-	ah->listen_time = 0;
-
-	return listen_time;
-}
-
 static void ath9k_ani_reset_old(struct ath_hw *ah, bool is_scanning)
 {
 	struct ar5416AniState *aniState;
@@ -655,7 +643,9 @@ static void ath9k_hw_ani_read_counters(struct ath_hw *ah)
 	u32 phyCnt1, phyCnt2;
 	int32_t listenTime;
 
-	listenTime = ath9k_hw_ani_get_listen_time(ah);
+	ath_hw_cycle_counters_update(common);
+	listenTime = ath_hw_get_listen_time(common);
+
 	if (listenTime < 0) {
 		ah->stats.ast_ani_lneg++;
 		ath9k_ani_restart(ah);
@@ -796,54 +786,6 @@ void ath9k_hw_disable_mib_counters(struct ath_hw *ah)
 }
 EXPORT_SYMBOL(ath9k_hw_disable_mib_counters);
 
-void ath9k_hw_update_cycle_counters(struct ath_hw *ah)
-{
-	struct ath_cycle_counters cc;
-	bool clear;
-
-	memcpy(&cc, &ah->cc, sizeof(cc));
-
-	/* freeze counters */
-	REG_WRITE(ah, AR_MIBC, AR_MIBC_FMC);
-
-	ah->cc.cycles = REG_READ(ah, AR_CCCNT);
-	if (ah->cc.cycles < cc.cycles) {
-		clear = true;
-		goto skip;
-	}
-
-	ah->cc.rx_clear = REG_READ(ah, AR_RCCNT);
-	ah->cc.rx_frame = REG_READ(ah, AR_RFCNT);
-	ah->cc.tx_frame = REG_READ(ah, AR_TFCNT);
-
-	/* prevent wraparound */
-	if (ah->cc.cycles & BIT(31))
-		clear = true;
-
-#define CC_DELTA(_field, _reg) ah->cc_delta._field += ah->cc._field - cc._field
-	CC_DELTA(cycles, AR_CCCNT);
-	CC_DELTA(rx_frame, AR_RFCNT);
-	CC_DELTA(rx_clear, AR_RCCNT);
-	CC_DELTA(tx_frame, AR_TFCNT);
-#undef CC_DELTA
-
-	ah->listen_time += (ah->cc.cycles - cc.cycles) -
-		 ((ah->cc.rx_frame - cc.rx_frame) +
-		  (ah->cc.tx_frame - cc.tx_frame));
-
-skip:
-	if (clear) {
-		REG_WRITE(ah, AR_CCCNT, 0);
-		REG_WRITE(ah, AR_RFCNT, 0);
-		REG_WRITE(ah, AR_RCCNT, 0);
-		REG_WRITE(ah, AR_TFCNT, 0);
-		memset(&ah->cc, 0, sizeof(ah->cc));
-	}
-
-	/* unfreeze counters */
-	REG_WRITE(ah, AR_MIBC, 0);
-}
-
 /*
  * Process a MIB interrupt.  We may potentially be invoked because
  * any of the MIB counters overflow/trigger so don't assume we're
diff --git a/drivers/net/wireless/ath/ath9k/ani.h b/drivers/net/wireless/ath/ath9k/ani.h
index 98cfd81..0cd6783 100644
--- a/drivers/net/wireless/ath/ath9k/ani.h
+++ b/drivers/net/wireless/ath/ath9k/ani.h
@@ -93,13 +93,6 @@ struct ath9k_mib_stats {
 	u32 beacons;
 };
 
-struct ath_cycle_counters {
-	u32 cycles;
-	u32 rx_frame;
-	u32 rx_clear;
-	u32 tx_frame;
-};
-
 /* INI default values for ANI registers */
 struct ath9k_ani_default {
 	u16 m1ThreshLow;
@@ -164,7 +157,6 @@ struct ar5416Stats {
 
 void ath9k_enable_mib_counters(struct ath_hw *ah);
 void ath9k_hw_disable_mib_counters(struct ath_hw *ah);
-void ath9k_hw_update_cycle_counters(struct ath_hw *ah);
 void ath9k_hw_ani_setup(struct ath_hw *ah);
 void ath9k_hw_ani_init(struct ath_hw *ah);
 int ath9k_hw_get_ani_channel_idx(struct ath_hw *ah,
diff --git a/drivers/net/wireless/ath/ath9k/ar9003_phy.c b/drivers/net/wireless/ath/ath9k/ar9003_phy.c
index efb0559..669b777 100644
--- a/drivers/net/wireless/ath/ath9k/ar9003_phy.c
+++ b/drivers/net/wireless/ath/ath9k/ar9003_phy.c
@@ -1254,13 +1254,12 @@ void ar9003_hw_bb_watchdog_dbg_info(struct ath_hw *ah)
 		  "** BB mode: BB_gen_controls=0x%08x **\n",
 		  REG_READ(ah, AR_PHY_GEN_CTRL));
 
-	ath9k_hw_update_cycle_counters(ah);
-#define PCT(_field) (ah->cc_delta._field * 100 / ah->cc_delta.cycles)
-	if (ah->cc_delta.cycles)
+#define PCT(_field) (common->cc_survey._field * 100 / common->cc_survey.cycles)
+	if (common->cc_survey.cycles)
 		ath_print(common, ATH_DBG_RESET,
 			  "** BB busy times: rx_clear=%d%%, "
 			  "rx_frame=%d%%, tx_frame=%d%% **\n",
-			  PCT(rx_clear), PCT(rx_frame), PCT(tx_frame));
+			  PCT(rx_busy), PCT(rx_frame), PCT(tx_frame));
 
 	ath_print(common, ATH_DBG_RESET,
 		  "==== BB update: done ====\n\n");
diff --git a/drivers/net/wireless/ath/ath9k/hw.h b/drivers/net/wireless/ath/ath9k/hw.h
index 87627dd..7f696c8 100644
--- a/drivers/net/wireless/ath/ath9k/hw.h
+++ b/drivers/net/wireless/ath/ath9k/hw.h
@@ -740,8 +740,6 @@ struct ath_hw {
 	int coarse_low[5];
 	int firpwr[5];
 	enum ath9k_ani_cmd ani_function;
-	struct ath_cycle_counters cc, cc_delta;
-	int32_t listen_time;
 
 	/* Bluetooth coexistance */
 	struct ath_btcoex_hw btcoex_hw;
diff --git a/drivers/net/wireless/ath/ath9k/main.c b/drivers/net/wireless/ath/ath9k/main.c
index 74c2dc8..360c6f5 100644
--- a/drivers/net/wireless/ath/ath9k/main.c
+++ b/drivers/net/wireless/ath/ath9k/main.c
@@ -399,6 +399,7 @@ void ath_ani_calibrate(unsigned long data)
 	bool aniflag = false;
 	unsigned int timestamp = jiffies_to_msecs(jiffies);
 	u32 cal_interval, short_cal_interval, long_cal_interval;
+	unsigned long flags;
 
 	if (ah->caldata && ah->caldata->nfcal_interference)
 		long_cal_interval = ATH_LONG_CALINTERVAL_INT;
@@ -449,8 +450,11 @@ void ath_ani_calibrate(unsigned long data)
 	/* Skip all processing if there's nothing to do. */
 	if (longcal || shortcal || aniflag) {
 		/* Call ANI routine if necessary */
-		if (aniflag)
+		if (aniflag) {
+			spin_lock_irqsave(&common->cc_lock, flags);
 			ath9k_hw_ani_monitor(ah, ah->curchan);
+			spin_unlock_irqrestore(&common->cc_lock, flags);
+		}
 
 		/* Perform calibration if necessary */
 		if (longcal || shortcal) {
@@ -635,6 +639,7 @@ irqreturn_t ath_isr(int irq, void *dev)
 
 	struct ath_softc *sc = dev;
 	struct ath_hw *ah = sc->sc_ah;
+	struct ath_common *common = ath9k_hw_common(ah);
 	enum ath9k_int status;
 	bool sched = false;
 
@@ -684,7 +689,12 @@ irqreturn_t ath_isr(int irq, void *dev)
 
 	if ((ah->caps.hw_caps & ATH9K_HW_CAP_EDMA) &&
 	    (status & ATH9K_INT_BB_WATCHDOG)) {
+
+		spin_lock(&common->cc_lock);
+		ath_hw_cycle_counters_update(common);
 		ar9003_hw_bb_watchdog_dbg_info(ah);
+		spin_unlock(&common->cc_lock);
+
 		goto chip_reset;
 	}
 
diff --git a/drivers/net/wireless/ath/ath9k/reg.h b/drivers/net/wireless/ath/ath9k/reg.h
index 6d01e50..0176178 100644
--- a/drivers/net/wireless/ath/ath9k/reg.h
+++ b/drivers/net/wireless/ath/ath9k/reg.h
@@ -107,12 +107,6 @@
 #define AR_RXCFG_DMASZ_256B  6
 #define AR_RXCFG_DMASZ_512B  7
 
-#define AR_MIBC              0x0040
-#define AR_MIBC_COW          0x00000001
-#define AR_MIBC_FMC          0x00000002
-#define AR_MIBC_CMC          0x00000004
-#define AR_MIBC_MCS          0x00000008
-
 #define AR_TOPS              0x0044
 #define AR_TOPS_MASK         0x0000FFFF
 
@@ -1524,11 +1518,6 @@ enum {
 #define AR_TPC_CHIRP           0x003f0000
 #define AR_TPC_CHIRP_S         0x16
 
-#define AR_TFCNT           0x80ec
-#define AR_RFCNT           0x80f0
-#define AR_RCCNT           0x80f4
-#define AR_CCCNT           0x80f8
-
 #define AR_QUIET1          0x80fc
 #define AR_QUIET1_NEXT_QUIET_S         0
 #define AR_QUIET1_NEXT_QUIET_M         0x0000ffff
diff --git a/drivers/net/wireless/ath/hw.c b/drivers/net/wireless/ath/hw.c
index a8f81ea..183c282 100644
--- a/drivers/net/wireless/ath/hw.c
+++ b/drivers/net/wireless/ath/hw.c
@@ -124,3 +124,62 @@ void ath_hw_setbssidmask(struct ath_common *common)
 	REG_WRITE(ah, get_unaligned_le16(common->bssidmask + 4), AR_BSSMSKU);
 }
 EXPORT_SYMBOL(ath_hw_setbssidmask);
+
+
+/**
+ * ath_hw_cycle_counters_update - common function to update cycle counters
+ *
+ * @common: the ath_common struct for the device.
+ *
+ * This function is used to update all cycle counters in one place.
+ * It has to be called while holding common->cc_lock!
+ */
+void ath_hw_cycle_counters_update(struct ath_common *common)
+{
+	u32 cycles, busy, rx, tx;
+	void *ah = common->ah;
+
+	/* freeze */
+	REG_WRITE(ah, AR_MIBC_FMC, AR_MIBC);
+
+	/* read */
+	cycles = REG_READ(ah, AR_CCCNT);
+	busy = REG_READ(ah, AR_RCCNT);
+	rx = REG_READ(ah, AR_RFCNT);
+	tx = REG_READ(ah, AR_TFCNT);
+
+	/* clear */
+	REG_WRITE(ah, 0, AR_CCCNT);
+	REG_WRITE(ah, 0, AR_RFCNT);
+	REG_WRITE(ah, 0, AR_RCCNT);
+	REG_WRITE(ah, 0, AR_TFCNT);
+
+	/* unfreeze */
+	REG_WRITE(ah, 0, AR_MIBC);
+
+	/* update all cycle counters here */
+	common->cc_ani.cycles += cycles;
+	common->cc_ani.rx_busy += busy;
+	common->cc_ani.rx_frame += rx;
+	common->cc_ani.tx_frame += tx;
+
+	common->cc_survey.cycles += cycles;
+	common->cc_survey.rx_busy += busy;
+	common->cc_survey.rx_frame += rx;
+	common->cc_survey.tx_frame += tx;
+}
+EXPORT_SYMBOL(ath_hw_cycle_counters_update);
+
+int32_t ath_hw_get_listen_time(struct ath_common *common)
+{
+	struct ath_cycle_counters *cc = &common->cc_ani;
+	int32_t listen_time;
+
+	listen_time = (cc->cycles - cc->rx_frame - cc->tx_frame) /
+		      (common->clockrate * 1000);
+
+	memset(cc, 0, sizeof(*cc));
+
+	return listen_time;
+}
+EXPORT_SYMBOL(ath_hw_get_listen_time);
diff --git a/drivers/net/wireless/ath/reg.h b/drivers/net/wireless/ath/reg.h
index e798ef4..298e53f 100644
--- a/drivers/net/wireless/ath/reg.h
+++ b/drivers/net/wireless/ath/reg.h
@@ -17,6 +17,12 @@
 #ifndef ATH_REGISTERS_H
 #define ATH_REGISTERS_H
 
+#define AR_MIBC			0x0040
+#define AR_MIBC_COW		0x00000001
+#define AR_MIBC_FMC		0x00000002
+#define AR_MIBC_CMC		0x00000004
+#define AR_MIBC_MCS		0x00000008
+
 /*
  * BSSID mask registers. See ath_hw_set_bssid_mask()
  * for detailed documentation about these registers.
@@ -24,6 +30,11 @@
 #define AR_BSSMSKL		0x80e0
 #define AR_BSSMSKU		0x80e4
 
+#define AR_TFCNT		0x80ec
+#define AR_RFCNT		0x80f0
+#define AR_RCCNT		0x80f4
+#define AR_CCCNT		0x80f8
+
 #define AR_KEYTABLE_0           0x8800
 #define AR_KEYTABLE(_n)         (AR_KEYTABLE_0 + ((_n)*32))
 #define AR_KEY_CACHE_SIZE       128
-- 
1.7.2.2


^ permalink raw reply related	[flat|nested] 5+ messages in thread

* [PATCH 4/4] ath5k: use the common cycle counter / listen time implementation
  2010-10-08 20:13   ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Felix Fietkau
@ 2010-10-08 20:13     ` Felix Fietkau
  2010-10-15 21:40     ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Ben Greear
  1 sibling, 0 replies; 5+ messages in thread
From: Felix Fietkau @ 2010-10-08 20:13 UTC (permalink / raw)
  To: linux-wireless; +Cc: linville, lrodriguez, br1

Signed-off-by: Felix Fietkau <nbd@openwrt.org>
Signed-off-by: Bruno Randolf <br1@einfach.org>
---
 drivers/net/wireless/ath/ath5k/ani.c   |   41 +++++++++++---------------------
 drivers/net/wireless/ath/ath5k/ani.h   |    5 +---
 drivers/net/wireless/ath/ath5k/debug.c |   21 ++++++++-------
 3 files changed, 26 insertions(+), 41 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/ani.c b/drivers/net/wireless/ath/ath5k/ani.c
index e4a5f04..f141919 100644
--- a/drivers/net/wireless/ath/ath5k/ani.c
+++ b/drivers/net/wireless/ath/ath5k/ani.c
@@ -355,41 +355,28 @@ ath5k_ani_lower_immunity(struct ath5k_hw *ah, struct ath5k_ani_state *as)
 
 
 /**
- * ath5k_hw_ani_get_listen_time() - Calculate time spent listening
+ * ath5k_hw_ani_get_listen_time() - Update counters and return listening time
  *
  * Return an approximation of the time spent "listening" in milliseconds (ms)
- * since the last call of this function by deducting the cycles spent
- * transmitting and receiving from the total cycle count.
- * Save profile count values for debugging/statistics and because we might want
- * to use them later.
- *
- * We assume no one else clears these registers!
+ * since the last call of this function.
+ * Save a snapshot of the counter values for debugging/statistics.
  */
 static int
 ath5k_hw_ani_get_listen_time(struct ath5k_hw *ah, struct ath5k_ani_state *as)
 {
+	struct ath_common *common = ath5k_hw_common(ah);
 	int listen;
 
-	/* freeze */
-	ath5k_hw_reg_write(ah, AR5K_MIBC_FMC, AR5K_MIBC);
-	/* read */
-	as->pfc_cycles = ath5k_hw_reg_read(ah, AR5K_PROFCNT_CYCLE);
-	as->pfc_busy = ath5k_hw_reg_read(ah, AR5K_PROFCNT_RXCLR);
-	as->pfc_tx = ath5k_hw_reg_read(ah, AR5K_PROFCNT_TX);
-	as->pfc_rx = ath5k_hw_reg_read(ah, AR5K_PROFCNT_RX);
-	/* clear */
-	ath5k_hw_reg_write(ah, 0, AR5K_PROFCNT_TX);
-	ath5k_hw_reg_write(ah, 0, AR5K_PROFCNT_RX);
-	ath5k_hw_reg_write(ah, 0, AR5K_PROFCNT_RXCLR);
-	ath5k_hw_reg_write(ah, 0, AR5K_PROFCNT_CYCLE);
-	/* un-freeze */
-	ath5k_hw_reg_write(ah, 0, AR5K_MIBC);
-
-	/* TODO: where does 44000 come from? (11g clock rate?) */
-	listen = (as->pfc_cycles - as->pfc_rx - as->pfc_tx) / 44000;
-
-	if (as->pfc_cycles == 0 || listen < 0)
-		return 0;
+	spin_lock_bh(&common->cc_lock);
+
+	ath_hw_cycle_counters_update(common);
+	memcpy(&as->last_cc, &common->cc_ani, sizeof(as->last_cc));
+
+	/* clears common->cc_ani */
+	listen = ath_hw_get_listen_time(common);
+
+	spin_unlock_bh(&common->cc_lock);
+
 	return listen;
 }
 
diff --git a/drivers/net/wireless/ath/ath5k/ani.h b/drivers/net/wireless/ath/ath5k/ani.h
index 55cf26d..d0a6640 100644
--- a/drivers/net/wireless/ath/ath5k/ani.h
+++ b/drivers/net/wireless/ath/ath5k/ani.h
@@ -75,10 +75,7 @@ struct ath5k_ani_state {
 	unsigned int		cck_errors;
 
 	/* debug/statistics only: numbers from last ANI calibration */
-	unsigned int		pfc_tx;
-	unsigned int		pfc_rx;
-	unsigned int		pfc_busy;
-	unsigned int		pfc_cycles;
+	struct ath_cycle_counters last_cc;
 	unsigned int		last_listen;
 	unsigned int		last_ofdm_errors;
 	unsigned int		last_cck_errors;
diff --git a/drivers/net/wireless/ath/ath5k/debug.c b/drivers/net/wireless/ath/ath5k/debug.c
index c2d549f..1506d1d 100644
--- a/drivers/net/wireless/ath/ath5k/debug.c
+++ b/drivers/net/wireless/ath/ath5k/debug.c
@@ -715,20 +715,21 @@ static ssize_t read_file_ani(struct file *file, char __user *user_buf,
 	len += snprintf(buf+len, sizeof(buf)-len,
 			"beacon RSSI average:\t%d\n",
 			sc->ah->ah_beacon_rssi_avg.avg);
+
+#define CC_PRINT(_struct, _field) \
+	_struct._field, \
+	_struct.cycles > 0 ? \
+	_struct._field*100/_struct.cycles : 0
+
 	len += snprintf(buf+len, sizeof(buf)-len, "profcnt tx\t\t%u\t(%d%%)\n",
-			as->pfc_tx,
-			as->pfc_cycles > 0 ?
-			as->pfc_tx*100/as->pfc_cycles : 0);
+			CC_PRINT(as->last_cc, tx_frame));
 	len += snprintf(buf+len, sizeof(buf)-len, "profcnt rx\t\t%u\t(%d%%)\n",
-			as->pfc_rx,
-			as->pfc_cycles > 0 ?
-			as->pfc_rx*100/as->pfc_cycles : 0);
+			CC_PRINT(as->last_cc, rx_frame));
 	len += snprintf(buf+len, sizeof(buf)-len, "profcnt busy\t\t%u\t(%d%%)\n",
-			as->pfc_busy,
-			as->pfc_cycles > 0 ?
-			as->pfc_busy*100/as->pfc_cycles : 0);
+			CC_PRINT(as->last_cc, rx_busy));
+#undef CC_PRINT
 	len += snprintf(buf+len, sizeof(buf)-len, "profcnt cycles\t\t%u\n",
-			as->pfc_cycles);
+			as->last_cc.cycles);
 	len += snprintf(buf+len, sizeof(buf)-len,
 			"listen time\t\t%d\tlast: %d\n",
 			as->listen_time, as->last_listen);
-- 
1.7.2.2


^ permalink raw reply related	[flat|nested] 5+ messages in thread

* Re: [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath
  2010-10-08 20:13   ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Felix Fietkau
  2010-10-08 20:13     ` [PATCH 4/4] ath5k: use the common cycle counter / listen time implementation Felix Fietkau
@ 2010-10-15 21:40     ` Ben Greear
  1 sibling, 0 replies; 5+ messages in thread
From: Ben Greear @ 2010-10-15 21:40 UTC (permalink / raw)
  To: Felix Fietkau; +Cc: linux-wireless, linville, lrodriguez, br1

On 10/08/2010 01:13 PM, Felix Fietkau wrote:
> Instead of keeping track of wraparound, clear the counters on every
> access and keep separate deltas for ANI and later survey use.
> Also moves the function for calculating the 'listen time' for ANI

> @@ -147,6 +155,10 @@ struct ath_common {
>
>   	unsigned int clockrate;
>
> +	spinlock_t cc_lock;
> +	struct ath_cycle_counters cc_ani;
> +	struct ath_cycle_counters cc_survey;

I don't see where cc_lock is ever initialized properly.  I think
that is what is causing this lockdep splat:

INFO: trying to register non-static key.
the code is fine but needs lockdep annotation.
turning off the locking correctness validator.
Pid: 2240, comm: ip Not tainted 2.6.36-rc8-wl+ #32
Call Trace:
  [<c075d940>] ? printk+0xf/0x17
  [<c045507a>] register_lock_class+0x5a/0x29e
  [<c0455be2>] ? mark_lock+0x1e/0x1de
  [<c0456af5>] __lock_acquire+0xa2/0xb8c
  [<c0455be2>] ? mark_lock+0x1e/0x1de
  [<c0457639>] lock_acquire+0x5a/0x78
  [<f8c5115b>] ? ath9k_config+0x274/0x3d8 [ath9k]
  [<c075f602>] _raw_spin_lock_irqsave+0x2f/0x3f
  [<f8c5115b>] ? ath9k_config+0x274/0x3d8 [ath9k]
  [<f8c5115b>] ath9k_config+0x274/0x3d8 [ath9k]
  [<f8c0ba2e>] ieee80211_hw_config+0x11b/0x125 [mac80211]
  [<f8c17edf>] ieee80211_do_open+0x3c5/0x466 [mac80211]
  [<f8c171d6>] ? ieee80211_check_concurrent_iface+0x21/0x13a [mac80211]
  [<f8c17fdb>] ieee80211_open+0x5b/0x5e [mac80211]
  [<c06ce76b>] __dev_open+0x80/0xae
  [<c06cc99b>] __dev_change_flags+0xa0/0x115
  [<c06ce6bf>] dev_change_flags+0x13/0x3f
  [<c06d7e78>] do_setlink+0x23a/0x51b
  [<c0455037>] ? register_lock_class+0x17/0x29e
  [<c06d847c>] rtnl_newlink+0x269/0x431
  [<c06d8291>] ? rtnl_newlink+0x7e/0x431
  [<c0455be2>] ? mark_lock+0x1e/0x1de
  [<c0455de9>] ? mark_held_locks+0x47/0x5f
  [<c075ebcf>] ? __mutex_lock_common+0x2bb/0x2d6
  [<c0456045>] ? trace_hardirqs_on_caller+0x104/0x125
  [<c075ebe0>] ? __mutex_lock_common+0x2cc/0x2d6
  [<c06d8213>] ? rtnl_newlink+0x0/0x431
  [<c06d79e2>] rtnetlink_rcv_msg+0x182/0x198
  [<c06d7860>] ? rtnetlink_rcv_msg+0x0/0x198
  [<c06e503c>] netlink_rcv_skb+0x30/0x77
  [<c06d7859>] rtnetlink_rcv+0x1b/0x22
  [<c06e4e77>] netlink_unicast+0xbe/0x119
  [<c06e5a15>] netlink_sendmsg+0x234/0x24c
  [<c06bf93a>] __sock_sendmsg+0x51/0x5a
  [<c06bfba4>] sock_sendmsg+0x93/0xa7
  [<c04968cf>] ? might_fault+0x47/0x81
  [<c0496904>] ? might_fault+0x7c/0x81
  [<c06c7904>] ? copy_from_user+0x8/0xa
  [<c06c7c2d>] ? verify_iovec+0x3e/0x6d
  [<c06bfd8c>] sys_sendmsg+0x149/0x193
  [<c0455037>] ? register_lock_class+0x17/0x29e
  [<c0455be2>] ? mark_lock+0x1e/0x1de
  [<c0498d7a>] ? __do_fault+0x1fc/0x3a5
  [<c048690a>] ? unlock_page+0x40/0x43
  [<c0498ef7>] ? __do_fault+0x379/0x3a5
  [<c04576dd>] ? lock_release_non_nested+0x86/0x1d8
  [<c04968cf>] ? might_fault+0x47/0x81
  [<c04968cf>] ? might_fault+0x47/0x81
  [<c06c148b>] sys_socketcall+0x15e/0x1a5
  [<c0402f1c>] sysenter_do_call+0x12/0x38
ADDRCONF(NETDEV_UP): wlan0: link is not ready
ieee80211 phy0: device no longer idle - scanning

-- 
Ben Greear <greearb@candelatech.com>
Candela Technologies Inc  http://www.candelatech.com


^ permalink raw reply	[flat|nested] 5+ messages in thread

end of thread, other threads:[~2010-10-15 21:40 UTC | newest]

Thread overview: 5+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2010-10-08 20:13 [PATCH 1/4] ath9k_hw: store the clock rate in common data on channel changes Felix Fietkau
2010-10-08 20:13 ` [PATCH 2/4] ath5k: " Felix Fietkau
2010-10-08 20:13   ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Felix Fietkau
2010-10-08 20:13     ` [PATCH 4/4] ath5k: use the common cycle counter / listen time implementation Felix Fietkau
2010-10-15 21:40     ` [PATCH 3/4] ath9k_hw: move the cycle counter tracking to ath Ben Greear

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).