linux-wireless.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH 0/5] ath5k updates
@ 2009-07-04 16:59 Bob Copeland
  2009-07-04 16:59 ` [PATCH 1/5] ath5k: send buffered frames after the beacon Bob Copeland
                   ` (4 more replies)
  0 siblings, 5 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-04 16:59 UTC (permalink / raw)
  To: linville, jirislaby, mickflemm, lrodriguez
  Cc: linux-wireless, ath5k-devel, Bob Copeland

I've been sitting on these patches for much too long.  But anyway,
here are some updates for ath5k.  1-2 fix beacon issues, 3 is just
minor cleanup that I had sitting around forever, 4 is a reported
suspend/resume issue from Alan Jenkins, and 5 is a reported
initialization issue from Forrest Zhang.

Bob Copeland (5):
  ath5k: send buffered frames after the beacon
  ath5k: rework beacon configuration
  ath: remove unnecessary return in ath_regd_get_band_ctl
  ath5k: do not release irq across suspend/resume
  ath5k: write PCU registers on initial reset

 drivers/net/wireless/ath/ath5k/base.c |  107 +++++++++++++++-----------------
 drivers/net/wireless/ath/ath5k/base.h |   10 ++--
 drivers/net/wireless/ath/ath5k/qcu.c  |    1 -
 drivers/net/wireless/ath/regd.c       |    2 -
 4 files changed, 55 insertions(+), 65 deletions(-)



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

* [PATCH 1/5] ath5k: send buffered frames after the beacon
  2009-07-04 16:59 [PATCH 0/5] ath5k updates Bob Copeland
@ 2009-07-04 16:59 ` Bob Copeland
  2009-07-04 16:59 ` [PATCH 2/5] ath5k: rework beacon configuration Bob Copeland
                   ` (3 subsequent siblings)
  4 siblings, 0 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-04 16:59 UTC (permalink / raw)
  To: linville, jirislaby, mickflemm, lrodriguez
  Cc: linux-wireless, ath5k-devel, Bob Copeland

Enable the "Content" After Beacon queue and utilize it to send
any buffered frames for power-saving clients.

Signed-off-by: Bob Copeland <me@bobcopeland.com>
---
 drivers/net/wireless/ath/ath5k/base.c |   35 ++++++++++++++++++++++++++++----
 drivers/net/wireless/ath/ath5k/base.h |    9 +++----
 drivers/net/wireless/ath/ath5k/qcu.c  |    1 -
 3 files changed, 34 insertions(+), 11 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/base.c b/drivers/net/wireless/ath/ath5k/base.c
index c6e7091..87ebc46 100644
--- a/drivers/net/wireless/ath/ath5k/base.c
+++ b/drivers/net/wireless/ath/ath5k/base.c
@@ -218,6 +218,8 @@ static struct pci_driver ath5k_pci_driver = {
  * Prototypes - MAC 802.11 stack related functions
  */
 static int ath5k_tx(struct ieee80211_hw *hw, struct sk_buff *skb);
+static int ath5k_tx_queue(struct ieee80211_hw *hw, struct sk_buff *skb,
+		struct ath5k_txq *txq);
 static int ath5k_reset(struct ath5k_softc *sc, struct ieee80211_channel *chan);
 static int ath5k_reset_wake(struct ath5k_softc *sc);
 static int ath5k_start(struct ieee80211_hw *hw);
@@ -301,7 +303,8 @@ static void	ath5k_desc_free(struct ath5k_softc *sc,
 static int 	ath5k_rxbuf_setup(struct ath5k_softc *sc,
 				struct ath5k_buf *bf);
 static int 	ath5k_txbuf_setup(struct ath5k_softc *sc,
-				struct ath5k_buf *bf);
+				struct ath5k_buf *bf,
+				struct ath5k_txq *txq);
 static inline void ath5k_txbuf_free(struct ath5k_softc *sc,
 				struct ath5k_buf *bf)
 {
@@ -516,6 +519,7 @@ ath5k_pci_probe(struct pci_dev *pdev,
 	/* Initialize driver private data */
 	SET_IEEE80211_DEV(hw, &pdev->dev);
 	hw->flags = IEEE80211_HW_RX_INCLUDES_FCS |
+		    IEEE80211_HW_HOST_BROADCAST_PS_BUFFERING |
 		    IEEE80211_HW_SIGNAL_DBM |
 		    IEEE80211_HW_NOISE_DBM;
 
@@ -789,12 +793,18 @@ ath5k_attach(struct pci_dev *pdev, struct ieee80211_hw *hw)
 		goto err_desc;
 	}
 	sc->bhalq = ret;
+	sc->cabq = ath5k_txq_setup(sc, AR5K_TX_QUEUE_CAB, 0);
+	if (IS_ERR(sc->cabq)) {
+		ATH5K_ERR(sc, "can't setup cab queue\n");
+		ret = PTR_ERR(sc->cabq);
+		goto err_bhal;
+	}
 
 	sc->txq = ath5k_txq_setup(sc, AR5K_TX_QUEUE_DATA, AR5K_WME_AC_BK);
 	if (IS_ERR(sc->txq)) {
 		ATH5K_ERR(sc, "can't setup xmit queue\n");
 		ret = PTR_ERR(sc->txq);
-		goto err_bhal;
+		goto err_queues;
 	}
 
 	tasklet_init(&sc->rxtq, ath5k_tasklet_rx, (unsigned long)sc);
@@ -1232,10 +1242,10 @@ ath5k_rxbuf_setup(struct ath5k_softc *sc, struct ath5k_buf *bf)
 }
 
 static int
-ath5k_txbuf_setup(struct ath5k_softc *sc, struct ath5k_buf *bf)
+ath5k_txbuf_setup(struct ath5k_softc *sc, struct ath5k_buf *bf,
+		  struct ath5k_txq *txq)
 {
 	struct ath5k_hw *ah = sc->ah;
-	struct ath5k_txq *txq = sc->txq;
 	struct ath5k_desc *ds = bf->desc;
 	struct sk_buff *skb = bf->skb;
 	struct ieee80211_tx_info *info = IEEE80211_SKB_CB(skb);
@@ -2103,6 +2113,7 @@ ath5k_beacon_send(struct ath5k_softc *sc)
 {
 	struct ath5k_buf *bf = sc->bbuf;
 	struct ath5k_hw *ah = sc->ah;
+	struct sk_buff *skb;
 
 	ATH5K_DBG_UNLIMIT(sc, ATH5K_DEBUG_BEACON, "in beacon_send\n");
 
@@ -2156,6 +2167,12 @@ ath5k_beacon_send(struct ath5k_softc *sc)
 	ATH5K_DBG(sc, ATH5K_DEBUG_BEACON, "TXDP[%u] = %llx (%p)\n",
 		sc->bhalq, (unsigned long long)bf->daddr, bf->desc);
 
+	skb = ieee80211_get_buffered_bc(sc->hw, sc->vif);
+	while (skb) {
+		ath5k_tx_queue(sc->hw, skb, sc->cabq);
+		skb = ieee80211_get_buffered_bc(sc->hw, sc->vif);
+	}
+
 	sc->bsent++;
 }
 
@@ -2603,6 +2620,14 @@ static int
 ath5k_tx(struct ieee80211_hw *hw, struct sk_buff *skb)
 {
 	struct ath5k_softc *sc = hw->priv;
+
+	return ath5k_tx_queue(hw, skb, sc->txq);
+}
+
+static int ath5k_tx_queue(struct ieee80211_hw *hw, struct sk_buff *skb,
+			  struct ath5k_txq *txq)
+{
+	struct ath5k_softc *sc = hw->priv;
 	struct ath5k_buf *bf;
 	unsigned long flags;
 	int hdrlen;
@@ -2646,7 +2671,7 @@ ath5k_tx(struct ieee80211_hw *hw, struct sk_buff *skb)
 
 	bf->skb = skb;
 
-	if (ath5k_txbuf_setup(sc, bf)) {
+	if (ath5k_txbuf_setup(sc, bf, txq)) {
 		bf->skb = NULL;
 		spin_lock_irqsave(&sc->txbuflock, flags);
 		list_add_tail(&bf->list, &sc->txbuf);
diff --git a/drivers/net/wireless/ath/ath5k/base.h b/drivers/net/wireless/ath/ath5k/base.h
index f9b7f2f..65e75fb 100644
--- a/drivers/net/wireless/ath/ath5k/base.h
+++ b/drivers/net/wireless/ath/ath5k/base.h
@@ -114,8 +114,7 @@ struct ath5k_softc {
 	struct pci_dev		*pdev;		/* for dma mapping */
 	void __iomem		*iobase;	/* address of the device */
 	struct mutex		lock;		/* dev-level lock */
-	/* FIXME: how many does it really need? */
-	struct ieee80211_tx_queue_stats tx_stats[16];
+	struct ieee80211_tx_queue_stats tx_stats[AR5K_NUM_TX_QUEUES];
 	struct ieee80211_low_level_stats ll_stats;
 	struct ieee80211_hw	*hw;		/* IEEE 802.11 common */
 	struct ieee80211_supported_band sbands[IEEE80211_NUM_BANDS];
@@ -171,9 +170,8 @@ struct ath5k_softc {
 	struct list_head	txbuf;		/* transmit buffer */
 	spinlock_t		txbuflock;
 	unsigned int		txbuf_len;	/* buf count in txbuf list */
-	struct ath5k_txq	txqs[2];	/* beacon and tx */
-
-	struct ath5k_txq	*txq;		/* beacon and tx*/
+	struct ath5k_txq	txqs[AR5K_NUM_TX_QUEUES];	/* tx queues */
+	struct ath5k_txq	*txq;		/* main tx queue */
 	struct tasklet_struct	txtq;		/* tx intr tasklet */
 	struct ath5k_led	tx_led;		/* tx led */
 
@@ -187,6 +185,7 @@ struct ath5k_softc {
 				bintval,	/* beacon interval in TU */
 				bsent;
 	unsigned int		nexttbtt;	/* next beacon time in TU */
+	struct ath5k_txq	*cabq;		/* content after beacon */
 
 	struct timer_list	calib_tim;	/* calibration timer */
 	int 			power_level;	/* Requested tx power in dbm */
diff --git a/drivers/net/wireless/ath/ath5k/qcu.c b/drivers/net/wireless/ath/ath5k/qcu.c
index 73407b3..6d5aaf0 100644
--- a/drivers/net/wireless/ath/ath5k/qcu.c
+++ b/drivers/net/wireless/ath/ath5k/qcu.c
@@ -411,7 +411,6 @@ int ath5k_hw_reset_tx_queue(struct ath5k_hw *ah, unsigned int queue)
 			AR5K_REG_ENABLE_BITS(ah, AR5K_QUEUE_MISC(queue),
 				AR5K_QCU_MISC_FRSHED_BCN_SENT_GT |
 				AR5K_QCU_MISC_CBREXP_DIS |
-				AR5K_QCU_MISC_RDY_VEOL_POLICY |
 				AR5K_QCU_MISC_CBREXP_BCN_DIS);
 
 			ath5k_hw_reg_write(ah, ((AR5K_TUNE_BEACON_INTERVAL -
-- 
1.6.2.5



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

* [PATCH 2/5] ath5k: rework beacon configuration
  2009-07-04 16:59 [PATCH 0/5] ath5k updates Bob Copeland
  2009-07-04 16:59 ` [PATCH 1/5] ath5k: send buffered frames after the beacon Bob Copeland
@ 2009-07-04 16:59 ` Bob Copeland
  2009-07-04 16:59 ` [PATCH 3/5] ath: remove unnecessary return in ath_regd_get_band_ctl Bob Copeland
                   ` (2 subsequent siblings)
  4 siblings, 0 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-04 16:59 UTC (permalink / raw)
  To: linville, jirislaby, mickflemm, lrodriguez
  Cc: linux-wireless, ath5k-devel, Bob Copeland

Using the enable_beacon flag allows some simplifications and fixes
some corner cases in beacon handling.  This change adds a state
variable for beaconing in ath5k_beacon_config and handles both
enabling and disabling, thus eliminating the need for
ath5k_beacon_disable.  We also now configure the beacon when any
of the beacon parameters change, so ath5k_beacon_reconfig is no
longer needed (its mmiowb gets moved to ath5k_beacon_config).
Finally, by locking around the whole config function, we don't
need to worry about clearing the interrupt mask register before
installing the new mask.

The upshot is this correctly disables beaconing when the interfaces
are taken down, it fixes a potential restarting of beaconing
when ath5k_reset() is called, and ensures that updates to the
beacon interval take effect immediately.

Signed-off-by: Bob Copeland <me@bobcopeland.com>
---
 drivers/net/wireless/ath/ath5k/base.c |   59 ++++++++++----------------------
 drivers/net/wireless/ath/ath5k/base.h |    1 +
 2 files changed, 20 insertions(+), 40 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/base.c b/drivers/net/wireless/ath/ath5k/base.c
index 87ebc46..4829329 100644
--- a/drivers/net/wireless/ath/ath5k/base.c
+++ b/drivers/net/wireless/ath/ath5k/base.c
@@ -2093,13 +2093,6 @@ err_unmap:
 	return ret;
 }
 
-static void ath5k_beacon_disable(struct ath5k_softc *sc)
-{
-	sc->imask &= ~(AR5K_INT_BMISS | AR5K_INT_SWBA);
-	ath5k_hw_set_imr(sc->ah, sc->imask);
-	ath5k_hw_stop_tx_dma(sc->ah, sc->bhalq);
-}
-
 /*
  * Transmit a beacon frame at SWBA.  Dynamic updates to the
  * frame contents are done as needed and the slot time is
@@ -2293,13 +2286,11 @@ ath5k_beacon_config(struct ath5k_softc *sc)
 	struct ath5k_hw *ah = sc->ah;
 	unsigned long flags;
 
-	ath5k_hw_set_imr(ah, 0);
+	spin_lock_irqsave(&sc->block, flags);
 	sc->bmisscount = 0;
 	sc->imask &= ~(AR5K_INT_BMISS | AR5K_INT_SWBA);
 
-	if (sc->opmode == NL80211_IFTYPE_ADHOC ||
-			sc->opmode == NL80211_IFTYPE_MESH_POINT ||
-			sc->opmode == NL80211_IFTYPE_AP) {
+	if (sc->enable_beacon) {
 		/*
 		 * In IBSS mode we use a self-linked tx descriptor and let the
 		 * hardware send the beacons automatically. We have to load it
@@ -2312,16 +2303,17 @@ ath5k_beacon_config(struct ath5k_softc *sc)
 		sc->imask |= AR5K_INT_SWBA;
 
 		if (sc->opmode == NL80211_IFTYPE_ADHOC) {
-			if (ath5k_hw_hasveol(ah)) {
-				spin_lock_irqsave(&sc->block, flags);
+			if (ath5k_hw_hasveol(ah))
 				ath5k_beacon_send(sc);
-				spin_unlock_irqrestore(&sc->block, flags);
-			}
 		} else
 			ath5k_beacon_update_timers(sc, -1);
+	} else {
+		ath5k_hw_stop_tx_dma(sc->ah, sc->bhalq);
 	}
 
 	ath5k_hw_set_imr(ah, sc->imask);
+	mmiowb();
+	spin_unlock_irqrestore(&sc->block, flags);
 }
 
 static void ath5k_tasklet_beacon(unsigned long data)
@@ -2806,7 +2798,6 @@ ath5k_remove_interface(struct ieee80211_hw *hw,
 		goto end;
 
 	ath5k_hw_set_lladdr(sc->ah, mac);
-	ath5k_beacon_disable(sc);
 	sc->vif = NULL;
 end:
 	mutex_unlock(&sc->lock);
@@ -3135,25 +3126,6 @@ out:
 	return ret;
 }
 
-/*
- *  Update the beacon and reconfigure the beacon queues.
- */
-static void
-ath5k_beacon_reconfig(struct ieee80211_hw *hw, struct ieee80211_vif *vif)
-{
-	int ret;
-	unsigned long flags;
-	struct ath5k_softc *sc = hw->priv;
-
-	spin_lock_irqsave(&sc->block, flags);
-	ret = ath5k_beacon_update(hw, vif);
-	spin_unlock_irqrestore(&sc->block, flags);
-	if (ret == 0) {
-		ath5k_beacon_config(sc);
-		mmiowb();
-	}
-}
-
 static void
 set_beacon_filter(struct ieee80211_hw *hw, bool enable)
 {
@@ -3176,6 +3148,7 @@ static void ath5k_bss_info_changed(struct ieee80211_hw *hw,
 {
 	struct ath5k_softc *sc = hw->priv;
 	struct ath5k_hw *ah = sc->ah;
+	unsigned long flags;
 
 	mutex_lock(&sc->lock);
 	if (WARN_ON(sc->vif != vif))
@@ -3201,13 +3174,19 @@ static void ath5k_bss_info_changed(struct ieee80211_hw *hw,
 			AR5K_LED_ASSOC : AR5K_LED_INIT);
 	}
 
-	if (changes & BSS_CHANGED_BEACON &&
-	    (vif->type == NL80211_IFTYPE_ADHOC ||
-	     vif->type == NL80211_IFTYPE_MESH_POINT ||
-	     vif->type == NL80211_IFTYPE_AP)) {
-		ath5k_beacon_reconfig(hw, vif);
+	if (changes & BSS_CHANGED_BEACON) {
+		spin_lock_irqsave(&sc->block, flags);
+		ath5k_beacon_update(hw, vif);
+		spin_unlock_irqrestore(&sc->block, flags);
 	}
 
+	if (changes & BSS_CHANGED_BEACON_ENABLED)
+		sc->enable_beacon = bss_conf->enable_beacon;
+
+	if (changes & (BSS_CHANGED_BEACON | BSS_CHANGED_BEACON_ENABLED |
+		       BSS_CHANGED_BEACON_INT))
+		ath5k_beacon_config(sc);
+
  unlock:
 	mutex_unlock(&sc->lock);
 }
diff --git a/drivers/net/wireless/ath/ath5k/base.h b/drivers/net/wireless/ath/ath5k/base.h
index 65e75fb..778e422 100644
--- a/drivers/net/wireless/ath/ath5k/base.h
+++ b/drivers/net/wireless/ath/ath5k/base.h
@@ -190,6 +190,7 @@ struct ath5k_softc {
 	struct timer_list	calib_tim;	/* calibration timer */
 	int 			power_level;	/* Requested tx power in dbm */
 	bool			assoc;		/* assocate state */
+	bool			enable_beacon;	/* true if beacons are on */
 };
 
 #define ath5k_hw_hasbssidmask(_ah) \
-- 
1.6.2.5



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

* [PATCH 3/5] ath: remove unnecessary return in ath_regd_get_band_ctl
  2009-07-04 16:59 [PATCH 0/5] ath5k updates Bob Copeland
  2009-07-04 16:59 ` [PATCH 1/5] ath5k: send buffered frames after the beacon Bob Copeland
  2009-07-04 16:59 ` [PATCH 2/5] ath5k: rework beacon configuration Bob Copeland
@ 2009-07-04 16:59 ` Bob Copeland
  2009-07-04 16:59 ` [PATCH 4/5] ath5k: do not release irq across suspend/resume Bob Copeland
  2009-07-04 16:59 ` [PATCH 5/5] ath5k: write PCU registers on initial reset Bob Copeland
  4 siblings, 0 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-04 16:59 UTC (permalink / raw)
  To: linville, jirislaby, mickflemm, lrodriguez
  Cc: linux-wireless, ath5k-devel, Bob Copeland

'default' case already returns NO_CTL

Signed-off-by: Bob Copeland <me@bobcopeland.com>
---
 drivers/net/wireless/ath/regd.c |    2 --
 1 files changed, 0 insertions(+), 2 deletions(-)

diff --git a/drivers/net/wireless/ath/regd.c b/drivers/net/wireless/ath/regd.c
index eef370b..f37c832 100644
--- a/drivers/net/wireless/ath/regd.c
+++ b/drivers/net/wireless/ath/regd.c
@@ -569,7 +569,5 @@ u32 ath_regd_get_band_ctl(struct ath_regulatory *reg,
 	default:
 		return NO_CTL;
 	}
-
-	return NO_CTL;
 }
 EXPORT_SYMBOL(ath_regd_get_band_ctl);
-- 
1.6.2.5



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

* [PATCH 4/5] ath5k: do not release irq across suspend/resume
  2009-07-04 16:59 [PATCH 0/5] ath5k updates Bob Copeland
                   ` (2 preceding siblings ...)
  2009-07-04 16:59 ` [PATCH 3/5] ath: remove unnecessary return in ath_regd_get_band_ctl Bob Copeland
@ 2009-07-04 16:59 ` Bob Copeland
  2009-07-04 21:24   ` Jiri Slaby
  2009-07-04 16:59 ` [PATCH 5/5] ath5k: write PCU registers on initial reset Bob Copeland
  4 siblings, 1 reply; 12+ messages in thread
From: Bob Copeland @ 2009-07-04 16:59 UTC (permalink / raw)
  To: linville, jirislaby, mickflemm, lrodriguez
  Cc: linux-wireless, ath5k-devel, Bob Copeland, Rafael J. Wysocki

Paraphrasing Rafael J. Wysocki: "drivers should not release PCI IRQs
in suspend."  Doing so causes a warning during suspend/resume on some
platforms.

Cc: Rafael J. Wysocki <rjw@sisk.pl>
Reported-by: Alan Jenkins <alan-jenkins@tuffmail.co.uk>
Signed-off-by: Bob Copeland <me@bobcopeland.com>
---
 drivers/net/wireless/ath/ath5k/base.c |   11 -----------
 1 files changed, 0 insertions(+), 11 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/base.c b/drivers/net/wireless/ath/ath5k/base.c
index 4829329..3f55e90 100644
--- a/drivers/net/wireless/ath/ath5k/base.c
+++ b/drivers/net/wireless/ath/ath5k/base.c
@@ -674,7 +674,6 @@ ath5k_pci_suspend(struct pci_dev *pdev, pm_message_t state)
 
 	ath5k_led_off(sc);
 
-	free_irq(pdev->irq, sc);
 	pci_save_state(pdev);
 	pci_disable_device(pdev);
 	pci_set_power_state(pdev, PCI_D3hot);
@@ -702,18 +701,8 @@ ath5k_pci_resume(struct pci_dev *pdev)
 	 */
 	pci_write_config_byte(pdev, 0x41, 0);
 
-	err = request_irq(pdev->irq, ath5k_intr, IRQF_SHARED, "ath", sc);
-	if (err) {
-		ATH5K_ERR(sc, "request_irq failed\n");
-		goto err_no_irq;
-	}
-
 	ath5k_led_enable(sc);
 	return 0;
-
-err_no_irq:
-	pci_disable_device(pdev);
-	return err;
 }
 #endif /* CONFIG_PM */
 
-- 
1.6.2.5



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

* [PATCH 5/5] ath5k: write PCU registers on initial reset
  2009-07-04 16:59 [PATCH 0/5] ath5k updates Bob Copeland
                   ` (3 preceding siblings ...)
  2009-07-04 16:59 ` [PATCH 4/5] ath5k: do not release irq across suspend/resume Bob Copeland
@ 2009-07-04 16:59 ` Bob Copeland
  2009-07-04 18:40   ` Felix Fietkau
  4 siblings, 1 reply; 12+ messages in thread
From: Bob Copeland @ 2009-07-04 16:59 UTC (permalink / raw)
  To: linville, jirislaby, mickflemm, lrodriguez
  Cc: linux-wireless, ath5k-devel, Bob Copeland, stable

Commit d7dc100374df0c21afd8a198336ecd7999697159, "Ath5k: unify resets"
introduced a regression into 2.6.28 where the PCU registers are never
initialized, due to ath5k_reset() always passing true for change_channel.
We subsequently program a lot of these registers but several may start
in an unknown state.

Cc: stable@kernel.org
Reported-by: Forrest Zhang <forrest@hifulltech.com>
Signed-off-by: Bob Copeland <me@bobcopeland.com>
---
 drivers/net/wireless/ath/ath5k/base.c |    2 +-
 1 files changed, 1 insertions(+), 1 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/base.c b/drivers/net/wireless/ath/ath5k/base.c
index 3f55e90..80ae38d 100644
--- a/drivers/net/wireless/ath/ath5k/base.c
+++ b/drivers/net/wireless/ath/ath5k/base.c
@@ -2687,7 +2687,7 @@ ath5k_reset(struct ath5k_softc *sc, struct ieee80211_channel *chan)
 		sc->curchan = chan;
 		sc->curband = &sc->sbands[chan->band];
 	}
-	ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, true);
+	ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, chan == NULL);
 	if (ret) {
 		ATH5K_ERR(sc, "can't reset hardware (%d)\n", ret);
 		goto err;
-- 
1.6.2.5



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

* Re: [PATCH 5/5] ath5k: write PCU registers on initial reset
  2009-07-04 16:59 ` [PATCH 5/5] ath5k: write PCU registers on initial reset Bob Copeland
@ 2009-07-04 18:40   ` Felix Fietkau
  2009-07-05  0:41     ` Bob Copeland
  2009-07-05  1:03     ` Bob Copeland
  0 siblings, 2 replies; 12+ messages in thread
From: Felix Fietkau @ 2009-07-04 18:40 UTC (permalink / raw)
  To: Bob Copeland
  Cc: linville, jirislaby, mickflemm, lrodriguez, linux-wireless,
	ath5k-devel, stable

Bob Copeland wrote:
> Commit d7dc100374df0c21afd8a198336ecd7999697159, "Ath5k: unify resets"
> introduced a regression into 2.6.28 where the PCU registers are never
> initialized, due to ath5k_reset() always passing true for change_channel.
> We subsequently program a lot of these registers but several may start
> in an unknown state.
> 
> Cc: stable@kernel.org
> Reported-by: Forrest Zhang <forrest@hifulltech.com>
> Signed-off-by: Bob Copeland <me@bobcopeland.com>
> ---
>  drivers/net/wireless/ath/ath5k/base.c |    2 +-
>  1 files changed, 1 insertions(+), 1 deletions(-)
> 
> diff --git a/drivers/net/wireless/ath/ath5k/base.c b/drivers/net/wireless/ath/ath5k/base.c
> index 3f55e90..80ae38d 100644
> --- a/drivers/net/wireless/ath/ath5k/base.c
> +++ b/drivers/net/wireless/ath/ath5k/base.c
> @@ -2687,7 +2687,7 @@ ath5k_reset(struct ath5k_softc *sc, struct ieee80211_channel *chan)
>  		sc->curchan = chan;
>  		sc->curband = &sc->sbands[chan->band];
>  	}
> -	ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, true);
> +	ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, chan == NULL);
Shouldn't this be chan != NULL? I'd assume that chan is NULL the first
time and change_channel thus should be false to initialize all the
registers.

- Felix

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

* Re: [PATCH 4/5] ath5k: do not release irq across suspend/resume
  2009-07-04 16:59 ` [PATCH 4/5] ath5k: do not release irq across suspend/resume Bob Copeland
@ 2009-07-04 21:24   ` Jiri Slaby
  2009-07-04 21:37     ` Rafael J. Wysocki
  0 siblings, 1 reply; 12+ messages in thread
From: Jiri Slaby @ 2009-07-04 21:24 UTC (permalink / raw)
  To: Bob Copeland
  Cc: linville, mickflemm, lrodriguez, linux-wireless, ath5k-devel,
	Rafael J. Wysocki

On 07/04/2009 06:59 PM, Bob Copeland wrote:
> Paraphrasing Rafael J. Wysocki: "drivers should not release PCI IRQs
> in suspend."  Doing so causes a warning during suspend/resume on some
> platforms.

Hmm, I added it because I was told an irq can change over suspend (or at
least it could in the past). I think it's not true anymore, since we
would have serious problems with the code all over the tree.

I can't find where Rafael uttered those words above, do you have a link?

> Cc: Rafael J. Wysocki <rjw@sisk.pl>
> Reported-by: Alan Jenkins <alan-jenkins@tuffmail.co.uk>
> Signed-off-by: Bob Copeland <me@bobcopeland.com>

Signed-off-by: Jiri Slaby <jirislaby@gmail.com>

Thanks.

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

* Re: [PATCH 4/5] ath5k: do not release irq across suspend/resume
  2009-07-04 21:24   ` Jiri Slaby
@ 2009-07-04 21:37     ` Rafael J. Wysocki
  2009-07-05 11:53       ` Bob Copeland
  0 siblings, 1 reply; 12+ messages in thread
From: Rafael J. Wysocki @ 2009-07-04 21:37 UTC (permalink / raw)
  To: Jiri Slaby
  Cc: Bob Copeland, linville, mickflemm, lrodriguez, linux-wireless,
	ath5k-devel

On Saturday 04 July 2009, Jiri Slaby wrote:
> On 07/04/2009 06:59 PM, Bob Copeland wrote:
> > Paraphrasing Rafael J. Wysocki: "drivers should not release PCI IRQs
> > in suspend."  Doing so causes a warning during suspend/resume on some
> > platforms.
> 
> Hmm, I added it because I was told an irq can change over suspend (or at
> least it could in the past). I think it's not true anymore, since we
> would have serious problems with the code all over the tree.
> 
> I can't find where Rafael uttered those words above, do you have a link?

Someone recently asked on a mailing list (unfortunately I can't recall
which one) if drivers should release irqs over suspend.

The answer was more-or-less that drivers are not expected to do that and it
really is not recommended.  In fact, we do the whole suspend_device_irqs()
thing, because the drivers are expected not to do that.

Best,
Rafael

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

* Re: [PATCH 5/5] ath5k: write PCU registers on initial reset
  2009-07-04 18:40   ` Felix Fietkau
@ 2009-07-05  0:41     ` Bob Copeland
  2009-07-05  1:03     ` Bob Copeland
  1 sibling, 0 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-05  0:41 UTC (permalink / raw)
  To: Felix Fietkau
  Cc: linville, jirislaby, mickflemm, lrodriguez, linux-wireless,
	ath5k-devel, stable

>>       }
>> -     ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, true);
>> +     ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, chan == NULL);
>
> Shouldn't this be chan != NULL? I'd assume that chan is NULL the first
> time and change_channel thus should be false to initialize all the
> registers.

Yup, it should... I could swear I tested it, must've gotten lucky.

Thanks for the catch.

-- 
Bob Copeland %% www.bobcopeland.com

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

* [PATCH 5/5] ath5k: write PCU registers on initial reset
  2009-07-04 18:40   ` Felix Fietkau
  2009-07-05  0:41     ` Bob Copeland
@ 2009-07-05  1:03     ` Bob Copeland
  1 sibling, 0 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-05  1:03 UTC (permalink / raw)
  To: Felix Fietkau
  Cc: linville, jirislaby, mickflemm, lrodriguez, linux-wireless,
	ath5k-devel, stable

Commit d7dc100374df0c21afd8a198336ecd7999697159, "Ath5k: unify resets"
introduced a regression into 2.6.28 where the PCU registers are never
initialized, due to ath5k_reset() always passing true for change_channel.
We subsequently program a lot of these registers but several may start
in an unknown state.

Cc: stable@kernel.org
Reported-by: Forrest Zhang <forrest@hifulltech.com>
Signed-off-by: Bob Copeland <me@bobcopeland.com>
---

v2, without dumb thinko

 drivers/net/wireless/ath/ath5k/base.c |    2 +-
 1 files changed, 1 insertions(+), 1 deletions(-)

diff --git a/drivers/net/wireless/ath/ath5k/base.c b/drivers/net/wireless/ath/ath5k/base.c
index 3f55e90..80ae38d 100644
--- a/drivers/net/wireless/ath/ath5k/base.c
+++ b/drivers/net/wireless/ath/ath5k/base.c
@@ -2687,7 +2687,7 @@ ath5k_reset(struct ath5k_softc *sc, struct ieee80211_channel *chan)
 		sc->curchan = chan;
 		sc->curband = &sc->sbands[chan->band];
 	}
-	ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, true);
+	ret = ath5k_hw_reset(ah, sc->opmode, sc->curchan, chan != NULL);
 	if (ret) {
 		ATH5K_ERR(sc, "can't reset hardware (%d)\n", ret);
 		goto err;
-- 
1.6.2.5



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

* Re: [PATCH 4/5] ath5k: do not release irq across suspend/resume
  2009-07-04 21:37     ` Rafael J. Wysocki
@ 2009-07-05 11:53       ` Bob Copeland
  0 siblings, 0 replies; 12+ messages in thread
From: Bob Copeland @ 2009-07-05 11:53 UTC (permalink / raw)
  To: Rafael J. Wysocki
  Cc: Jiri Slaby, linville, mickflemm, lrodriguez, linux-wireless,
	ath5k-devel

On Sat, Jul 04, 2009 at 11:37:58PM +0200, Rafael J. Wysocki wrote:
> Someone recently asked on a mailing list (unfortunately I can't recall
> which one) if drivers should release irqs over suspend.

Yeah, it was linux-wireless.  Original message is here:

http://marc.info/?l=linux-wireless&m=124515641807355

(The paraphrasing is rather liberal but that was the gist.)
-- 
Bob Copeland %% www.bobcopeland.com


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

end of thread, other threads:[~2009-07-05 11:54 UTC | newest]

Thread overview: 12+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2009-07-04 16:59 [PATCH 0/5] ath5k updates Bob Copeland
2009-07-04 16:59 ` [PATCH 1/5] ath5k: send buffered frames after the beacon Bob Copeland
2009-07-04 16:59 ` [PATCH 2/5] ath5k: rework beacon configuration Bob Copeland
2009-07-04 16:59 ` [PATCH 3/5] ath: remove unnecessary return in ath_regd_get_band_ctl Bob Copeland
2009-07-04 16:59 ` [PATCH 4/5] ath5k: do not release irq across suspend/resume Bob Copeland
2009-07-04 21:24   ` Jiri Slaby
2009-07-04 21:37     ` Rafael J. Wysocki
2009-07-05 11:53       ` Bob Copeland
2009-07-04 16:59 ` [PATCH 5/5] ath5k: write PCU registers on initial reset Bob Copeland
2009-07-04 18:40   ` Felix Fietkau
2009-07-05  0:41     ` Bob Copeland
2009-07-05  1:03     ` Bob Copeland

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).