2013-02-06 11:49:13

by Marco Porsch

[permalink] [raw]
Subject: [RFCv2 0/3] mesh power save - hardware doze

Commits #2 and #3 implement the actual power saving mechanism
for mesh.

When the current peer link states allow doze state, the HW is
configured accordingly.
STA wake up from doze state for
1) sending their own beacon and tailing awake window
2) receiving beacons of peers they are in light sleep towards
In these two situations a Mesh Peer Service Period may be
initiated to extend the awake phase to transmit/receive
frames.

Design goal was to implement most PS routines in mac80211 to
keep maintainability high and allow simple driver adaption.
Since mesh PS requires waiting for beacon/multicasts (CAB) per
STA, these routines are re-implemented in mac80211.

The implementation should be capable of managing multiple
concurrent mesh vif, although this has rarely been tested, yet.

(For more info see https://github.com/cozybit/open80211s/wiki
/Mesh-Powersave-Implementation-Notes.)

On some test devices (WNDR3700/3800 with openwrt r35284) I
experience frequent crashes ("Data bus error"). Adding udelay
to ath9k_hw_set_power_awake and ath9k_set_power_network_sleep as
described in https://dev.openwrt.org/ticket/9107 seems to help.
I am unsure if I just stumble over a bug or cause it myself
here.

v2:
mac80211:
- trigger wakeups in HW (Johannes)
- got rid of hrtimer usage (Johannes)
- got rid of pre-TBTT wakeup margin
- got rid of HW sleep/awake status variable in local
- fix deep sleep wakeup schedule
ath9k:
- program HW's TIM timer registers to perform wakeups

Marco Porsch (3):
mac80211: move mesh sync beacon handler into neighbour_update
mac80211: mesh power save doze scheduling
ath9k: mesh powersave support

drivers/net/wireless/ath/ath9k/ath9k.h | 1 +
drivers/net/wireless/ath/ath9k/beacon.c | 21 +-
drivers/net/wireless/ath/ath9k/hw.c | 20 +-
drivers/net/wireless/ath/ath9k/main.c | 67 ++++++-
include/net/mac80211.h | 29 +++
net/mac80211/ieee80211_i.h | 17 +-
net/mac80211/mesh.c | 25 ++-
net/mac80211/mesh.h | 22 ++-
net/mac80211/mesh_plink.c | 17 +-
net/mac80211/mesh_ps.c | 316 +++++++++++++++++++++++++++++++
net/mac80211/mesh_sync.c | 47 ++---
net/mac80211/sta_info.c | 3 +
net/mac80211/sta_info.h | 10 +
net/mac80211/tx.c | 2 +
14 files changed, 541 insertions(+), 56 deletions(-)

--
1.7.9.5



2013-02-08 21:57:54

by Johannes Berg

[permalink] [raw]
Subject: Re: [RFCv2 2/3] mac80211: mesh power save doze scheduling

On Fri, 2013-02-08 at 11:09 +0100, Marco Porsch wrote:

> >> For mesh Awake Windows wakeup on SWBA (beacon_get_tim) and start
> >> a timer which triggers a doze call on expiry.
> >
> > That seems questionable -- drivers are not required to request each
> > beacon. I know you only want to make it work on ath9k, but I don't think
> > "stretching" the API, without even documenting it, is a good idea.
>
> Currently, we already use ieee80211_beacon_get_tim as time reference for
> mesh sync's adjust_tbtt. And, as far as I know, all mesh-capable drivers
> use the call for each and every beacon.

Oops, why did I miss that before? :-)

> So what would you recommend: keep using beacon_get and adding
> documentation - or - creating an exported callback for awake_window_start?

I guess you could add it... However, I don't really fully understand.
There's no guarantee that fetching the beacon is done anywhere close to
TBTT? Or does ath9k happen to do it just after TXing a beacon? You're
encoding quite a lot of ath9k-specific assumptions here it seems?

johannes


2013-02-06 11:49:16

by Marco Porsch

[permalink] [raw]
Subject: [RFCv2 3/3] ath9k: mesh powersave support

Register mesh PS ops on interface add and de-register on
removal.

React to doze/wakeup calls issued by mac80211.
Add a PS status flag PS_MAC80211_CTL to store last mesh PS
command from mac80211.

On doze call configure the HW to wakeup on the given TSF value.

Signed-off-by: Marco Porsch <[email protected]>
---
drivers/net/wireless/ath/ath9k/ath9k.h | 1 +
drivers/net/wireless/ath/ath9k/beacon.c | 21 +++++++++-
drivers/net/wireless/ath/ath9k/hw.c | 20 ++++++---
drivers/net/wireless/ath/ath9k/main.c | 67 ++++++++++++++++++++++++++++++-
4 files changed, 101 insertions(+), 8 deletions(-)

diff --git a/drivers/net/wireless/ath/ath9k/ath9k.h b/drivers/net/wireless/ath/ath9k/ath9k.h
index b2d6c18..3dc83e5 100644
--- a/drivers/net/wireless/ath/ath9k/ath9k.h
+++ b/drivers/net/wireless/ath/ath9k/ath9k.h
@@ -650,6 +650,7 @@ enum sc_op_flags {
#define PS_WAIT_FOR_TX_ACK BIT(3)
#define PS_BEACON_SYNC BIT(4)
#define PS_WAIT_FOR_ANI BIT(5)
+#define PS_MAC80211_CTL BIT(6)

struct ath_rate_table;

diff --git a/drivers/net/wireless/ath/ath9k/beacon.c b/drivers/net/wireless/ath/ath9k/beacon.c
index dd37719..7ef698b 100644
--- a/drivers/net/wireless/ath/ath9k/beacon.c
+++ b/drivers/net/wireless/ath/ath9k/beacon.c
@@ -599,6 +599,23 @@ static void ath9k_beacon_config_adhoc(struct ath_softc *sc,
ath9k_beacon_init(sc, nexttbtt, intval);
}

+static void ath9k_beacon_config_mesh(struct ath_softc *sc,
+ struct ath_beacon_config *conf)
+{
+ struct ath9k_beacon_state bs;
+
+ /*
+ * when PS is enabled, ath9k_hw_setrxabort is set.
+ * to wake up again to receive peers' beacons, we set an
+ * arbitrary initial value for sleepduration here
+ */
+ memset(&bs, 0, sizeof(bs));
+ bs.bs_sleepduration = IEEE80211_MS_TO_TU(100);
+ ath9k_hw_set_sta_beacon_timers(sc->sc_ah, &bs);
+
+ ath9k_beacon_config_adhoc(sc, conf);
+}
+
bool ath9k_allow_beacon_config(struct ath_softc *sc, struct ieee80211_vif *vif)
{
struct ath_common *common = ath9k_hw_common(sc->sc_ah);
@@ -707,9 +724,11 @@ void ath9k_set_beacon(struct ath_softc *sc)
ath9k_beacon_config_ap(sc, cur_conf);
break;
case NL80211_IFTYPE_ADHOC:
- case NL80211_IFTYPE_MESH_POINT:
ath9k_beacon_config_adhoc(sc, cur_conf);
break;
+ case NL80211_IFTYPE_MESH_POINT:
+ ath9k_beacon_config_mesh(sc, cur_conf);
+ break;
case NL80211_IFTYPE_STATION:
ath9k_beacon_config_sta(sc, cur_conf);
break;
diff --git a/drivers/net/wireless/ath/ath9k/hw.c b/drivers/net/wireless/ath/ath9k/hw.c
index 42cf3c7..f851678 100644
--- a/drivers/net/wireless/ath/ath9k/hw.c
+++ b/drivers/net/wireless/ath/ath9k/hw.c
@@ -2254,16 +2254,24 @@ void ath9k_hw_beaconinit(struct ath_hw *ah, u32 next_beacon, u32 beacon_period)
}
EXPORT_SYMBOL(ath9k_hw_beaconinit);

+/**
+ * ath9k_hw_set_sta_beacon_timers
+ *
+ * in mesh mode overwriting AR_NEXT_TBTT_TIMER and setting AR_TBTT_TIMER_EN
+ * would shift the own TBTT
+ * TODO rename?
+ */
void ath9k_hw_set_sta_beacon_timers(struct ath_hw *ah,
const struct ath9k_beacon_state *bs)
{
- u32 nextTbtt, beaconintval, dtimperiod, beacontimeout;
+ u32 nextTbtt, beaconintval, dtimperiod, beacontimeout, ar_timer_mode;
struct ath9k_hw_capabilities *pCap = &ah->caps;
struct ath_common *common = ath9k_hw_common(ah);

ENABLE_REGWRITE_BUFFER(ah);

- REG_WRITE(ah, AR_NEXT_TBTT_TIMER, TU_TO_USEC(bs->bs_nexttbtt));
+ if (ah->opmode != NL80211_IFTYPE_MESH_POINT)
+ REG_WRITE(ah, AR_NEXT_TBTT_TIMER, TU_TO_USEC(bs->bs_nexttbtt));

REG_WRITE(ah, AR_BEACON_PERIOD,
TU_TO_USEC(bs->bs_intval));
@@ -2317,9 +2325,11 @@ void ath9k_hw_set_sta_beacon_timers(struct ath_hw *ah,

REGWRITE_BUFFER_FLUSH(ah);

- REG_SET_BIT(ah, AR_TIMER_MODE,
- AR_TBTT_TIMER_EN | AR_TIM_TIMER_EN |
- AR_DTIM_TIMER_EN);
+ ar_timer_mode = AR_DTIM_TIMER_EN | AR_TIM_TIMER_EN;
+ if (ah->opmode != NL80211_IFTYPE_MESH_POINT)
+ ar_timer_mode |= AR_TBTT_TIMER_EN;
+
+ REG_SET_BIT(ah, AR_TIMER_MODE, ar_timer_mode);

/* TSF Out of Range Threshold */
REG_WRITE(ah, AR_TSFOOR_THRESHOLD, bs->bs_tsfoor_threshold);
diff --git a/drivers/net/wireless/ath/ath9k/main.c b/drivers/net/wireless/ath/ath9k/main.c
index 4b72b66..a4e6623 100644
--- a/drivers/net/wireless/ath/ath9k/main.c
+++ b/drivers/net/wireless/ath/ath9k/main.c
@@ -132,7 +132,8 @@ void ath9k_ps_restore(struct ath_softc *sc)
PS_WAIT_FOR_CAB |
PS_WAIT_FOR_PSPOLL_DATA |
PS_WAIT_FOR_TX_ACK |
- PS_WAIT_FOR_ANI))) {
+ PS_WAIT_FOR_ANI |
+ PS_MAC80211_CTL))) {
mode = ATH9K_PM_NETWORK_SLEEP;
if (ath9k_hw_btcoex_is_enabled(sc->sc_ah))
ath9k_btcoex_stop_gen_timer(sc);
@@ -821,6 +822,63 @@ static void ath9k_stop(struct ieee80211_hw *hw)
ath_dbg(common, CONFIG, "Driver halt\n");
}

+static void ath9k_mesh_wakeup_set(struct ath_softc *sc, u64 nexttbtt)
+{
+ struct ath_hw *ah = sc->sc_ah;
+ struct ath9k_beacon_state bs;
+ u32 nexttbtttu = TSF_TO_TU(nexttbtt >> 32, nexttbtt);
+
+ memset(&bs, 0, sizeof(bs));
+ bs.bs_nexttbtt = nexttbtttu;
+ bs.bs_nextdtim = nexttbtttu;
+ /*
+ * arbitrary values to avoid frequent wakeups,
+ * high enough to not interfere with nexttbtt
+ * TODO adaptive
+ */
+ bs.bs_intval = 1000;
+ bs.bs_dtimperiod = 4000;
+ bs.bs_sleepduration = 1000;
+
+ ath9k_hw_set_sta_beacon_timers(ah, &bs);
+}
+
+static void ath9k_mesh_doze(struct ieee80211_hw *hw, u64 nexttbtt)
+{
+ struct ath_softc *sc = hw->priv;
+ unsigned long flags;
+
+ ath9k_ps_wakeup(sc);
+ spin_lock_irqsave(&sc->sc_pm_lock, flags);
+ /* in mesh mode mac80211 checks beacons and CAB */
+ sc->ps_flags &= ~(PS_WAIT_FOR_BEACON |
+ PS_WAIT_FOR_CAB |
+ PS_MAC80211_CTL);
+ spin_unlock_irqrestore(&sc->sc_pm_lock, flags);
+
+ if (nexttbtt)
+ ath9k_mesh_wakeup_set(sc, nexttbtt);
+
+ ath9k_ps_restore(sc);
+}
+
+static void ath9k_mesh_wakeup(struct ieee80211_hw *hw)
+{
+ struct ath_softc *sc = hw->priv;
+ unsigned long flags;
+
+ ath9k_ps_wakeup(sc);
+ spin_lock_irqsave(&sc->sc_pm_lock, flags);
+ sc->ps_flags |= PS_MAC80211_CTL;
+ spin_unlock_irqrestore(&sc->sc_pm_lock, flags);
+ ath9k_ps_restore(sc);
+}
+
+static const struct ieee80211_mps_ops ath9k_mesh_ps_ops = {
+ .hw_doze = ath9k_mesh_doze,
+ .hw_wakeup = ath9k_mesh_wakeup,
+};
+
bool ath9k_uses_beacons(int type)
{
switch (type) {
@@ -931,6 +989,11 @@ static void ath9k_calculate_summary_state(struct ieee80211_hw *hw,
ah->opmode = NL80211_IFTYPE_ADHOC;
else
ah->opmode = NL80211_IFTYPE_STATION;
+
+ if (ah->opmode == NL80211_IFTYPE_MESH_POINT)
+ ieee80211_mps_init(hw, &ath9k_mesh_ps_ops);
+ else if (old_opmode == NL80211_IFTYPE_MESH_POINT)
+ ieee80211_mps_init(hw, NULL);
}

ath9k_hw_setopmode(ah);
@@ -1175,7 +1238,7 @@ static int ath9k_config(struct ieee80211_hw *hw, u32 changed)
* We just prepare to enable PS. We have to wait until our AP has
* ACK'd our null data frame to disable RX otherwise we'll ignore
* those ACKs and end up retransmitting the same null data frames.
- * IEEE80211_CONF_CHANGE_PS is only passed by mac80211 for STA mode.
+ * IEEE80211_CONF_CHANGE_PS is passed by mac80211 for STA or mesh mode.
*/
if (changed & IEEE80211_CONF_CHANGE_PS) {
unsigned long flags;
--
1.7.9.5


2013-02-08 10:09:21

by Marco Porsch

[permalink] [raw]
Subject: Re: [RFCv2 2/3] mac80211: mesh power save doze scheduling

On 02/08/2013 10:20 AM, Johannes Berg wrote:
> On Wed, 2013-02-06 at 12:48 +0100, Marco Porsch wrote:
>
>> For mesh Awake Windows wakeup on SWBA (beacon_get_tim) and start
>> a timer which triggers a doze call on expiry.
>
> That seems questionable -- drivers are not required to request each
> beacon. I know you only want to make it work on ath9k, but I don't think
> "stretching" the API, without even documenting it, is a good idea.

Currently, we already use ieee80211_beacon_get_tim as time reference for
mesh sync's adjust_tbtt. And, as far as I know, all mesh-capable drivers
use the call for each and every beacon.
So what would you recommend: keep using beacon_get and adding
documentation - or - creating an exported callback for awake_window_start?

>> +static inline void mps_queue_work(struct ieee80211_sub_if_data *sdata,
>> + enum mesh_deferred_task_flags flag)
>> +{
>> + set_bit(flag, &sdata->u.mesh.wrkq_flags);
>> + ieee80211_queue_work(&sdata->local->hw, &sdata->work);
>> +}
>
> Doing any sort of wakeup from here is also undesirable -- the workqueue
> might actually sometimes be blocked for quite a while, I believe.

Yeah, right. Now that the hrtimer stuff is gone, I will check if the
remaining contexts allows skipping the work queue for wakeups.

>> +/**
>> + * ieee80211_mps_hw_conf - check conditions for mesh PS and configure driver
>> + *
>> + * @sdata: local mesh subif
>> + */
>> +void ieee80211_mps_hw_conf(struct ieee80211_sub_if_data *sdata)
>> +{
>> + struct ieee80211_local *local = sdata->local;
>> + bool enable;
>> +
>> + enable = mps_hw_conf_check(local);
>> +
>> + if (local->mps_enabled == enable)
>> + return;
>> +
>> + if (enable) {
>> + mps_hw_conf_sta_prepare(local);
>> + local->hw.conf.flags |= IEEE80211_CONF_PS;
>> + } else {
>> + local->hw.conf.flags &= ~IEEE80211_CONF_PS;
>> + }
>> +
>> + ieee80211_hw_config(local, IEEE80211_CONF_CHANGE_PS);
>
> For some reason I thought this was supposed to be covered by the new
> mesh PS callbacks, why do you still need hw conf?
>
> Or wait -- this is only for general enable/disable, depending on the
> other interfaces? I guess that's ok.
>
>> + /* simple Deep Sleep implementation: only wake up for DTIM beacons */
>> + if (sta->local_pm == NL80211_MESH_POWER_DEEP_SLEEP)
>> + skip = tim->dtim_count ? tim->dtim_count : tim->dtim_period;
>> + /*
>> + * determine time to peer TBTT (TSF % beacon_interval = 0).
>> + * This approach is robust to delayed beacons.
>> + */
>> + tsf_peer = tsf_local + sta->t_offset;
>> + nexttbtt_interval = sta->beacon_interval * skip -
>> + do_div(tsf_peer, sta->beacon_interval * skip);
>> +
>> + mps_dbg(sta->sdata, "updating %pM next TBTT in %dus (%lldus awake)\n",
>> + sta->sta.addr, nexttbtt_interval,
>> + (long long) tsf_local - sta->nexttbtt_tsf);
>> +
>> + sta->nexttbtt_tsf = tsf_local + nexttbtt_interval;
>> + sta->nexttbtt_jiffies = jiffies + usecs_to_jiffies(nexttbtt_interval);
>> +
>> + mod_timer(&sta->nexttbtt_timer, sta->nexttbtt_jiffies +
>> + usecs_to_jiffies(BEACON_TIMEOUT));
>
> Is that some sort of recovery? jiffies can be up to 20ms (I think, in
> that order of magnitude anyway) inaccurate.

Yeah, that timer just hits as recovery in case a beacon is not received.
Then it projects the next TBTT and goes to sleep again.

Thanks,
--Marco


2013-02-06 11:49:14

by Marco Porsch

[permalink] [raw]
Subject: [RFCv2 1/3] mac80211: move mesh sync beacon handler into neighbour_update

Move the beacon handler into mesh_neighbour_update where the STA
pointer is already available. This avoids additional overhead
and simplifies the handler.
The repositioning will also benefit mesh PS which uses the
T_offset value right after it has been updated.

Rename the handler to better reflect its purpose.

Signed-off-by: Marco Porsch <[email protected]>
---
net/mac80211/ieee80211_i.h | 10 +++++-----
net/mac80211/mesh.c | 8 ++------
net/mac80211/mesh.h | 5 +++--
net/mac80211/mesh_plink.c | 16 ++++++++++++---
net/mac80211/mesh_sync.c | 47 +++++++++++++++-----------------------------
5 files changed, 39 insertions(+), 47 deletions(-)

diff --git a/net/mac80211/ieee80211_i.h b/net/mac80211/ieee80211_i.h
index 650f758..bba2b10 100644
--- a/net/mac80211/ieee80211_i.h
+++ b/net/mac80211/ieee80211_i.h
@@ -560,11 +560,11 @@ struct ieee80211_if_ibss {
*/
struct ieee802_11_elems;
struct ieee80211_mesh_sync_ops {
- void (*rx_bcn_presp)(struct ieee80211_sub_if_data *sdata,
- u16 stype,
- struct ieee80211_mgmt *mgmt,
- struct ieee802_11_elems *elems,
- struct ieee80211_rx_status *rx_status);
+ void (*rx_bcn)(struct sta_info *sta,
+ struct ieee80211_mgmt *mgmt,
+ struct ieee802_11_elems *elems,
+ struct ieee80211_rx_status *rx_status,
+ u64 tsf);
void (*adjust_tbtt)(struct ieee80211_sub_if_data *sdata);
/* add other framework functions here */
};
diff --git a/net/mac80211/mesh.c b/net/mac80211/mesh.c
index e39a3f8..643262b 100644
--- a/net/mac80211/mesh.c
+++ b/net/mac80211/mesh.c
@@ -714,7 +714,6 @@ static void ieee80211_mesh_rx_bcn_presp(struct ieee80211_sub_if_data *sdata,
struct ieee80211_rx_status *rx_status)
{
struct ieee80211_local *local = sdata->local;
- struct ieee80211_if_mesh *ifmsh = &sdata->u.mesh;
struct ieee802_11_elems elems;
struct ieee80211_channel *channel;
size_t baselen;
@@ -750,13 +749,10 @@ static void ieee80211_mesh_rx_bcn_presp(struct ieee80211_sub_if_data *sdata,
return;

if (mesh_matches_local(sdata, &elems))
- mesh_neighbour_update(sdata, mgmt->sa, &elems);
-
- if (ifmsh->sync_ops)
- ifmsh->sync_ops->rx_bcn_presp(sdata,
- stype, mgmt, &elems, rx_status);
+ mesh_neighbour_update(sdata, mgmt, &elems, rx_status);
}

+
static void ieee80211_mesh_rx_mgmt_action(struct ieee80211_sub_if_data *sdata,
struct ieee80211_mgmt *mgmt,
size_t len,
diff --git a/net/mac80211/mesh.h b/net/mac80211/mesh.h
index eb33625..d6d9933 100644
--- a/net/mac80211/mesh.h
+++ b/net/mac80211/mesh.h
@@ -283,8 +283,9 @@ int mesh_path_send_to_gates(struct mesh_path *mpath);
int mesh_gate_num(struct ieee80211_sub_if_data *sdata);
/* Mesh plinks */
void mesh_neighbour_update(struct ieee80211_sub_if_data *sdata,
- u8 *hw_addr,
- struct ieee802_11_elems *ie);
+ struct ieee80211_mgmt *mgmt,
+ struct ieee802_11_elems *ie,
+ struct ieee80211_rx_status *rx_status);
bool mesh_peer_accepts_plinks(struct ieee802_11_elems *ie);
u32 mesh_accept_plinks_update(struct ieee80211_sub_if_data *sdata);
void mesh_plink_broken(struct sta_info *sta);
diff --git a/net/mac80211/mesh_plink.c b/net/mac80211/mesh_plink.c
index 57e7267..af6fbfd 100644
--- a/net/mac80211/mesh_plink.c
+++ b/net/mac80211/mesh_plink.c
@@ -12,6 +12,7 @@
#include "ieee80211_i.h"
#include "rate.h"
#include "mesh.h"
+#include "driver-ops.h"

#define PLINK_GET_LLID(p) (p + 2)
#define PLINK_GET_PLID(p) (p + 4)
@@ -391,13 +392,19 @@ static struct sta_info *mesh_peer_init(struct ieee80211_sub_if_data *sdata,
}

void mesh_neighbour_update(struct ieee80211_sub_if_data *sdata,
- u8 *hw_addr,
- struct ieee802_11_elems *elems)
+ struct ieee80211_mgmt *mgmt,
+ struct ieee802_11_elems *elems,
+ struct ieee80211_rx_status *rx_status)
{
+ struct ieee80211_if_mesh *ifmsh = &sdata->u.mesh;
struct sta_info *sta;
+ u64 tsf;
+
+ /* get tsf before entering rcu-read section */
+ tsf = drv_get_tsf(sdata->local, sdata);

rcu_read_lock();
- sta = mesh_peer_init(sdata, hw_addr, elems);
+ sta = mesh_peer_init(sdata, mgmt->sa, elems);
if (!sta)
goto out;

@@ -408,6 +415,9 @@ void mesh_neighbour_update(struct ieee80211_sub_if_data *sdata,
rssi_threshold_check(sta, sdata))
mesh_plink_open(sta);

+ if (ifmsh->sync_ops)
+ ifmsh->sync_ops->rx_bcn(sta, mgmt, elems, rx_status, tsf);
+
ieee80211_mps_frame_release(sta, elems);
out:
rcu_read_unlock();
diff --git a/net/mac80211/mesh_sync.c b/net/mac80211/mesh_sync.c
index aa8d1e4..2275de4 100644
--- a/net/mac80211/mesh_sync.c
+++ b/net/mac80211/mesh_sync.c
@@ -75,35 +75,23 @@ void mesh_sync_adjust_tbtt(struct ieee80211_sub_if_data *sdata)
drv_set_tsf(local, sdata, tsf + tsfdelta);
}

-static void mesh_sync_offset_rx_bcn_presp(struct ieee80211_sub_if_data *sdata,
- u16 stype,
- struct ieee80211_mgmt *mgmt,
- struct ieee802_11_elems *elems,
- struct ieee80211_rx_status *rx_status)
+static void mesh_sync_offset_rx_bcn(struct sta_info *sta,
+ struct ieee80211_mgmt *mgmt,
+ struct ieee802_11_elems *elems,
+ struct ieee80211_rx_status *rx_status,
+ u64 t_r)
{
+ struct ieee80211_sub_if_data *sdata = sta->sdata;
struct ieee80211_if_mesh *ifmsh = &sdata->u.mesh;
struct ieee80211_local *local = sdata->local;
- struct sta_info *sta;
- u64 t_t, t_r;
+ u64 t_t;

WARN_ON(ifmsh->mesh_sp_id != IEEE80211_SYNC_METHOD_NEIGHBOR_OFFSET);

/* standard mentions only beacons */
- if (stype != IEEE80211_STYPE_BEACON)
+ if (!ieee80211_is_beacon(mgmt->frame_control))
return;

- /* The current tsf is a first approximation for the timestamp
- * for the received beacon. Further down we try to get a
- * better value from the rx_status->mactime field if
- * available. Also we have to call drv_get_tsf() before
- * entering the rcu-read section.*/
- t_r = drv_get_tsf(local, sdata);
-
- rcu_read_lock();
- sta = sta_info_get(sdata, mgmt->sa);
- if (!sta)
- goto no_sync;
-
/* check offset sync conditions (13.13.2.2.1)
*
* TODO also sync to
@@ -113,11 +101,15 @@ static void mesh_sync_offset_rx_bcn_presp(struct ieee80211_sub_if_data *sdata,
if (elems->mesh_config && mesh_peer_tbtt_adjusting(elems)) {
clear_sta_flag(sta, WLAN_STA_TOFFSET_KNOWN);
msync_dbg(sdata, "STA %pM : is adjusting TBTT\n", sta->sta.addr);
- goto no_sync;
+ return;
}

+ /*
+ * The current tsf is a first approximation of the beacon RX time.
+ * If available, get a better value from the rx_status->mactime field
+ * (time when timestamp field was received).
+ */
if (ieee80211_have_rx_timestamp(rx_status))
- /* time when timestamp field was received */
t_r = ieee80211_calculate_rx_timestamp(local, rx_status,
24 + 12 +
elems->total_len +
@@ -146,11 +138,9 @@ static void mesh_sync_offset_rx_bcn_presp(struct ieee80211_sub_if_data *sdata,
sta->sta.addr,
(long long) t_clockdrift);
clear_sta_flag(sta, WLAN_STA_TOFFSET_KNOWN);
- goto no_sync;
+ return;
}

- rcu_read_unlock();
-
spin_lock_bh(&ifmsh->sync_offset_lock);
if (t_clockdrift >
ifmsh->sync_offset_clockdrift_max)
@@ -165,12 +155,7 @@ static void mesh_sync_offset_rx_bcn_presp(struct ieee80211_sub_if_data *sdata,
"STA %pM : offset was invalid, sta->t_offset=%lld\n",
sta->sta.addr,
(long long) sta->t_offset);
- rcu_read_unlock();
}
- return;
-
-no_sync:
- rcu_read_unlock();
}

static void mesh_sync_offset_adjust_tbtt(struct ieee80211_sub_if_data *sdata)
@@ -212,7 +197,7 @@ static const struct sync_method sync_methods[] = {
{
.method = IEEE80211_SYNC_METHOD_NEIGHBOR_OFFSET,
.ops = {
- .rx_bcn_presp = &mesh_sync_offset_rx_bcn_presp,
+ .rx_bcn = &mesh_sync_offset_rx_bcn,
.adjust_tbtt = &mesh_sync_offset_adjust_tbtt,
}
},
--
1.7.9.5


2013-02-11 12:03:53

by Marco Porsch

[permalink] [raw]
Subject: Re: [RFCv2 2/3] mac80211: mesh power save doze scheduling

On 02/08/2013 10:57 PM, Johannes Berg wrote:
> On Fri, 2013-02-08 at 11:09 +0100, Marco Porsch wrote:
>
>>>> For mesh Awake Windows wakeup on SWBA (beacon_get_tim) and start
>>>> a timer which triggers a doze call on expiry.
>>>
>>> That seems questionable -- drivers are not required to request each
>>> beacon. I know you only want to make it work on ath9k, but I don't think
>>> "stretching" the API, without even documenting it, is a good idea.
>>
>> Currently, we already use ieee80211_beacon_get_tim as time reference for
>> mesh sync's adjust_tbtt. And, as far as I know, all mesh-capable drivers
>> use the call for each and every beacon.
>
> Oops, why did I miss that before? :-)
>
>> So what would you recommend: keep using beacon_get and adding
>> documentation - or - creating an exported callback for awake_window_start?
>
> I guess you could add it... However, I don't really fully understand.
> There's no guarantee that fetching the beacon is done anywhere close to
> TBTT? Or does ath9k happen to do it just after TXing a beacon? You're
> encoding quite a lot of ath9k-specific assumptions here it seems?

I think the assumption is currently correct for ath5k, ath9k, ath9k_htc,
carl9170 and rt2800 (that's as far as I checked). All of these fetch a
beacon on SWBA/PRETBTT interrupt (more or less) immediately before TBTT.

--Marco

2013-02-08 09:20:39

by Johannes Berg

[permalink] [raw]
Subject: Re: [RFCv2 2/3] mac80211: mesh power save doze scheduling

On Wed, 2013-02-06 at 12:48 +0100, Marco Porsch wrote:

> For mesh Awake Windows wakeup on SWBA (beacon_get_tim) and start
> a timer which triggers a doze call on expiry.

That seems questionable -- drivers are not required to request each
beacon. I know you only want to make it work on ath9k, but I don't think
"stretching" the API, without even documenting it, is a good idea.

> +static inline void mps_queue_work(struct ieee80211_sub_if_data *sdata,
> + enum mesh_deferred_task_flags flag)
> +{
> + set_bit(flag, &sdata->u.mesh.wrkq_flags);
> + ieee80211_queue_work(&sdata->local->hw, &sdata->work);
> +}

Doing any sort of wakeup from here is also undesirable -- the workqueue
might actually sometimes be blocked for quite a while, I believe.

> +/**
> + * ieee80211_mps_hw_conf - check conditions for mesh PS and configure driver
> + *
> + * @sdata: local mesh subif
> + */
> +void ieee80211_mps_hw_conf(struct ieee80211_sub_if_data *sdata)
> +{
> + struct ieee80211_local *local = sdata->local;
> + bool enable;
> +
> + enable = mps_hw_conf_check(local);
> +
> + if (local->mps_enabled == enable)
> + return;
> +
> + if (enable) {
> + mps_hw_conf_sta_prepare(local);
> + local->hw.conf.flags |= IEEE80211_CONF_PS;
> + } else {
> + local->hw.conf.flags &= ~IEEE80211_CONF_PS;
> + }
> +
> + ieee80211_hw_config(local, IEEE80211_CONF_CHANGE_PS);

For some reason I thought this was supposed to be covered by the new
mesh PS callbacks, why do you still need hw conf?

Or wait -- this is only for general enable/disable, depending on the
other interfaces? I guess that's ok.

> + /* simple Deep Sleep implementation: only wake up for DTIM beacons */
> + if (sta->local_pm == NL80211_MESH_POWER_DEEP_SLEEP)
> + skip = tim->dtim_count ? tim->dtim_count : tim->dtim_period;
> + /*
> + * determine time to peer TBTT (TSF % beacon_interval = 0).
> + * This approach is robust to delayed beacons.
> + */
> + tsf_peer = tsf_local + sta->t_offset;
> + nexttbtt_interval = sta->beacon_interval * skip -
> + do_div(tsf_peer, sta->beacon_interval * skip);
> +
> + mps_dbg(sta->sdata, "updating %pM next TBTT in %dus (%lldus awake)\n",
> + sta->sta.addr, nexttbtt_interval,
> + (long long) tsf_local - sta->nexttbtt_tsf);
> +
> + sta->nexttbtt_tsf = tsf_local + nexttbtt_interval;
> + sta->nexttbtt_jiffies = jiffies + usecs_to_jiffies(nexttbtt_interval);
> +
> + mod_timer(&sta->nexttbtt_timer, sta->nexttbtt_jiffies +
> + usecs_to_jiffies(BEACON_TIMEOUT));

Is that some sort of recovery? jiffies can be up to 20ms (I think, in
that order of magnitude anyway) inaccurate.

johannes


2013-02-06 11:49:15

by Marco Porsch

[permalink] [raw]
Subject: [RFCv2 2/3] mac80211: mesh power save doze scheduling

Configure the HW for PS mode if the local mesh PS parameters
allow so.

Expose a callback ieee80211_mps_init for drivers to register
mesh powersave ops:
- hw_doze - put the radio to sleep now, wake up at given TBTT
- hw_wakeup - wake the radio up for frame RX
These ops may be extended in the future to allow drivers/HW to
implement mesh PS themselves. (The current design goal was to
concentrate most mesh PS routines in mac80211 to keep driver
modifications minimal.

Track the beacon timing information of peers we are in PS mode
towards. Calculate the next TBTT per-STA.

When going to doze state, get the most imminent STA TBTT and
configure the driver to trigger a wakeup on time to catch that
beacon. After successful receipt put the HW to doze again.
Set a timeout for the case that the beacon is not received on
time. In this case calculate the following TBTT and go to doze
again.

For mesh Awake Windows wakeup on SWBA (beacon_get_tim) and start
a timer which triggers a doze call on expiry.

Signed-off-by: Marco Porsch <[email protected]>
---
include/net/mac80211.h | 29 ++++
net/mac80211/ieee80211_i.h | 7 +-
net/mac80211/mesh.c | 17 +++
net/mac80211/mesh.h | 17 +++
net/mac80211/mesh_plink.c | 1 +
net/mac80211/mesh_ps.c | 316 ++++++++++++++++++++++++++++++++++++++++++++
net/mac80211/sta_info.c | 3 +
net/mac80211/sta_info.h | 10 ++
net/mac80211/tx.c | 2 +
9 files changed, 401 insertions(+), 1 deletion(-)

diff --git a/include/net/mac80211.h b/include/net/mac80211.h
index 3037f49..e393a49 100644
--- a/include/net/mac80211.h
+++ b/include/net/mac80211.h
@@ -3999,6 +3999,35 @@ void ieee80211_stop_rx_ba_session(struct ieee80211_vif *vif, u16 ba_rx_bitmap,
*/
void ieee80211_send_bar(struct ieee80211_vif *vif, u8 *ra, u16 tid, u16 ssn);

+/**
+ * struct ieee80211_mps_ops - callbacks from mac80211 to the driver for mesh PS
+ *
+ * @hw_doze: put the radio to doze state to conserve power, schedule wakeup
+ * at given TSF value to receive peer beacon
+ * @hw_wakeup: wake up the radio to receive frames again
+ */
+struct ieee80211_mps_ops {
+ void (*hw_doze)(struct ieee80211_hw *hw, u64 nexttbtt);
+ void (*hw_wakeup)(struct ieee80211_hw *hw);
+};
+
+#ifdef CONFIG_MAC80211_MESH
+/**
+ * ieee80211_mps_init - register callbacks for mesh PS
+ *
+ * @hw: the hardware
+ * @ops: callbacks for this device
+ *
+ * called by driver on mesh interface add/remove
+ */
+int ieee80211_mps_init(struct ieee80211_hw *hw,
+ const struct ieee80211_mps_ops *ops);
+#else
+static inline int ieee80211_mps_init(struct ieee80211_hw *hw,
+ const struct ieee80211_mps_ops *ops)
+{ return 0; }
+#endif
+
/* Rate control API */

/**
diff --git a/net/mac80211/ieee80211_i.h b/net/mac80211/ieee80211_i.h
index bba2b10..cb54bae 100644
--- a/net/mac80211/ieee80211_i.h
+++ b/net/mac80211/ieee80211_i.h
@@ -628,6 +628,7 @@ struct ieee80211_if_mesh {
int ps_peers_light_sleep;
int ps_peers_deep_sleep;
struct ps_data ps;
+ struct timer_list awake_window_end_timer;
};

#ifdef CONFIG_MAC80211_MESH
@@ -1125,7 +1126,7 @@ struct ieee80211_local {
bool pspolling;
bool offchannel_ps_enabled;
/*
- * PS can only be enabled when we have exactly one managed
+ * managed mode PS can only be enabled when we have exactly one managed
* interface (and monitors) in PS, this then points there.
*/
struct ieee80211_sub_if_data *ps_sdata;
@@ -1145,6 +1146,10 @@ struct ieee80211_local {

int user_power_level; /* in dBm, for all interfaces */

+ /* mesh power save */
+ bool mps_enabled;
+ const struct ieee80211_mps_ops *mps_ops;
+
enum ieee80211_smps_mode smps_mode;

struct work_struct restart_work;
diff --git a/net/mac80211/mesh.c b/net/mac80211/mesh.c
index 643262b..b0deb14 100644
--- a/net/mac80211/mesh.c
+++ b/net/mac80211/mesh.c
@@ -800,6 +800,7 @@ void ieee80211_mesh_rx_queued_mgmt(struct ieee80211_sub_if_data *sdata,

void ieee80211_mesh_work(struct ieee80211_sub_if_data *sdata)
{
+ struct ieee80211_local *local = sdata->local;
struct ieee80211_if_mesh *ifmsh = &sdata->u.mesh;

if (ifmsh->preq_queue_len &&
@@ -821,6 +822,19 @@ void ieee80211_mesh_work(struct ieee80211_sub_if_data *sdata)

if (test_and_clear_bit(MESH_WORK_DRIFT_ADJUST, &ifmsh->wrkq_flags))
mesh_sync_adjust_tbtt(sdata);
+
+ if (test_and_clear_bit(MESH_WORK_PS_HW_CONF, &ifmsh->wrkq_flags))
+ ieee80211_mps_hw_conf(sdata);
+
+ /* in case both fired simultaneously, wakeup overrides doze */
+ if (test_bit(MESH_WORK_PS_DOZE, &ifmsh->wrkq_flags) &&
+ test_bit(MESH_WORK_PS_WAKEUP, &ifmsh->wrkq_flags))
+ clear_bit(MESH_WORK_PS_DOZE, &ifmsh->wrkq_flags);
+
+ if (test_and_clear_bit(MESH_WORK_PS_WAKEUP, &ifmsh->wrkq_flags))
+ ieee80211_mps_wakeup(local);
+ else if (test_and_clear_bit(MESH_WORK_PS_DOZE, &ifmsh->wrkq_flags))
+ ieee80211_mps_doze(local);
}

void ieee80211_mesh_notify_scan_completed(struct ieee80211_local *local)
@@ -860,6 +874,9 @@ void ieee80211_mesh_init_sdata(struct ieee80211_sub_if_data *sdata)
setup_timer(&ifmsh->mesh_path_root_timer,
ieee80211_mesh_path_root_timer,
(unsigned long) sdata);
+ setup_timer(&ifmsh->awake_window_end_timer,
+ ieee80211_mps_awake_window_end,
+ (unsigned long) sdata);
INIT_LIST_HEAD(&ifmsh->preq_queue.list);
skb_queue_head_init(&ifmsh->ps.bc_buf);
spin_lock_init(&ifmsh->mesh_preq_queue_lock);
diff --git a/net/mac80211/mesh.h b/net/mac80211/mesh.h
index d6d9933..686f991 100644
--- a/net/mac80211/mesh.h
+++ b/net/mac80211/mesh.h
@@ -58,6 +58,10 @@ enum mesh_path_flags {
* @MESH_WORK_ROOT: the mesh root station needs to send a frame
* @MESH_WORK_DRIFT_ADJUST: time to compensate for clock drift relative to other
* mesh nodes
+ * @MESH_WORK_PS_HW_CONF: configure hardware according to the link-specific
+ * mesh power modes
+ * @MESH_WORK_PS_DOZE: put the hardware to sleep after checking all conditions
+ * @MESH_WORK_PS_WAKEUP: wakeup the hardware immediately
*/
enum mesh_deferred_task_flags {
MESH_WORK_HOUSEKEEPING,
@@ -65,6 +69,9 @@ enum mesh_deferred_task_flags {
MESH_WORK_GROW_MPP_TABLE,
MESH_WORK_ROOT,
MESH_WORK_DRIFT_ADJUST,
+ MESH_WORK_PS_HW_CONF,
+ MESH_WORK_PS_DOZE,
+ MESH_WORK_PS_WAKEUP,
};

/**
@@ -258,6 +265,16 @@ void ieee80211_mpsp_trigger_process(u8 *qc, struct sta_info *sta,
bool tx, bool acked);
void ieee80211_mps_frame_release(struct sta_info *sta,
struct ieee802_11_elems *elems);
+void ieee80211_mps_hw_conf(struct ieee80211_sub_if_data *sdata);
+void ieee80211_mps_sta_tbtt_update(struct sta_info *sta,
+ struct ieee80211_mgmt *mgmt,
+ struct ieee80211_tim_ie *tim,
+ u64 tsf);
+void ieee80211_mps_sta_tbtt_timeout(unsigned long data);
+void ieee80211_mps_awake_window_start(struct ieee80211_sub_if_data *sdata);
+void ieee80211_mps_awake_window_end(unsigned long data);
+void ieee80211_mps_doze(struct ieee80211_local *local);
+void ieee80211_mps_wakeup(struct ieee80211_local *local);

/* Mesh paths */
int mesh_nexthop_lookup(struct sk_buff *skb,
diff --git a/net/mac80211/mesh_plink.c b/net/mac80211/mesh_plink.c
index af6fbfd..f41b4bb 100644
--- a/net/mac80211/mesh_plink.c
+++ b/net/mac80211/mesh_plink.c
@@ -419,6 +419,7 @@ void mesh_neighbour_update(struct ieee80211_sub_if_data *sdata,
ifmsh->sync_ops->rx_bcn(sta, mgmt, elems, rx_status, tsf);

ieee80211_mps_frame_release(sta, elems);
+ ieee80211_mps_sta_tbtt_update(sta, mgmt, elems->tim, tsf);
out:
rcu_read_unlock();
}
diff --git a/net/mac80211/mesh_ps.c b/net/mac80211/mesh_ps.c
index b677962..08de056 100644
--- a/net/mac80211/mesh_ps.c
+++ b/net/mac80211/mesh_ps.c
@@ -9,6 +9,18 @@

#include "mesh.h"
#include "wme.h"
+#include <linux/export.h>
+
+
+#define BEACON_TIMEOUT 20000 /* in us units */
+
+
+static inline void mps_queue_work(struct ieee80211_sub_if_data *sdata,
+ enum mesh_deferred_task_flags flag)
+{
+ set_bit(flag, &sdata->u.mesh.wrkq_flags);
+ ieee80211_queue_work(&sdata->local->hw, &sdata->work);
+}


/* mesh PS management */
@@ -126,6 +138,8 @@ void ieee80211_mps_local_status_update(struct ieee80211_sub_if_data *sdata)

ifmsh->ps_peers_light_sleep = light_sleep_cnt;
ifmsh->ps_peers_deep_sleep = deep_sleep_cnt;
+
+ mps_queue_work(sdata, MESH_WORK_PS_HW_CONF);
}

/**
@@ -538,6 +552,12 @@ void ieee80211_mpsp_trigger_process(u8 *qc, struct sta_info *sta,
if (rspi && !test_and_set_sta_flag(sta, WLAN_STA_MPSP_OWNER))
mps_frame_deliver(sta, -1);
}
+
+ if (test_sta_flag(sta, WLAN_STA_MPSP_OWNER) ||
+ test_sta_flag(sta, WLAN_STA_MPSP_RECIPIENT))
+ mps_queue_work(sta->sdata, MESH_WORK_PS_WAKEUP);
+ else
+ mps_queue_work(sta->sdata, MESH_WORK_PS_DOZE);
}

/**
@@ -583,3 +603,299 @@ void ieee80211_mps_frame_release(struct sta_info *sta,
else
mps_frame_deliver(sta, 1);
}
+
+
+/* mesh PS driver configuration and doze scheduling */
+
+static bool mps_hw_conf_check(struct ieee80211_local *local)
+{
+ struct ieee80211_sub_if_data *sdata;
+ struct ieee80211_if_mesh *ifmsh;
+ bool enable = true;
+
+ if (!local->mps_ops)
+ return false;
+
+ mutex_lock(&local->iflist_mtx);
+ list_for_each_entry(sdata, &local->interfaces, list) {
+ if (!ieee80211_sdata_running(sdata))
+ continue;
+
+ /* If an AP or any other non-mesh vif is found, disable PS */
+ if (ieee80211_sdata_running(sdata) &&
+ sdata->vif.type != NL80211_IFTYPE_MESH_POINT) {
+ enable = false;
+ break;
+ }
+
+ ifmsh = &sdata->u.mesh;
+
+ /*
+ * check for non-peer power mode, check for links in active
+ * mode. Assume a valid power mode is set for each established
+ * peer link
+ */
+ if (ifmsh->nonpeer_pm == NL80211_MESH_POWER_ACTIVE ||
+ ifmsh->ps_peers_light_sleep + ifmsh->ps_peers_deep_sleep
+ < atomic_read(&ifmsh->estab_plinks)) {
+ enable = false;
+ break;
+ }
+ }
+ mutex_unlock(&local->iflist_mtx);
+
+ return enable;
+}
+
+/**
+ * mps_hw_conf_sta_prepare - mark peers to catch beacon once before first doze
+ */
+static void mps_hw_conf_sta_prepare(struct ieee80211_local *local)
+{
+ struct sta_info *sta;
+
+ mutex_lock(&local->sta_mtx);
+ list_for_each_entry(sta, &local->sta_list, list) {
+ if (!ieee80211_vif_is_mesh(&sta->sdata->vif) ||
+ !ieee80211_sdata_running(sta->sdata) ||
+ sta->plink_state != NL80211_PLINK_ESTAB)
+ continue;
+ else
+ set_sta_flag(sta, WLAN_STA_MPS_WAIT_FOR_CAB);
+ }
+ mutex_unlock(&local->sta_mtx);
+}
+
+/**
+ * ieee80211_mps_hw_conf - check conditions for mesh PS and configure driver
+ *
+ * @sdata: local mesh subif
+ */
+void ieee80211_mps_hw_conf(struct ieee80211_sub_if_data *sdata)
+{
+ struct ieee80211_local *local = sdata->local;
+ bool enable;
+
+ enable = mps_hw_conf_check(local);
+
+ if (local->mps_enabled == enable)
+ return;
+
+ if (enable) {
+ mps_hw_conf_sta_prepare(local);
+ local->hw.conf.flags |= IEEE80211_CONF_PS;
+ } else {
+ local->hw.conf.flags &= ~IEEE80211_CONF_PS;
+ }
+
+ ieee80211_hw_config(local, IEEE80211_CONF_CHANGE_PS);
+ local->mps_enabled = enable;
+ mps_queue_work(sdata, MESH_WORK_PS_WAKEUP);
+}
+
+static void mps_sta_nexttbtt_calc(struct sta_info *sta,
+ struct ieee80211_tim_ie *tim,
+ u64 tsf_local)
+{
+ u64 tsf_peer;
+ int skip = 1;
+ u32 nexttbtt_interval;
+
+ /* simple Deep Sleep implementation: only wake up for DTIM beacons */
+ if (sta->local_pm == NL80211_MESH_POWER_DEEP_SLEEP)
+ skip = tim->dtim_count ? tim->dtim_count : tim->dtim_period;
+ /*
+ * determine time to peer TBTT (TSF % beacon_interval = 0).
+ * This approach is robust to delayed beacons.
+ */
+ tsf_peer = tsf_local + sta->t_offset;
+ nexttbtt_interval = sta->beacon_interval * skip -
+ do_div(tsf_peer, sta->beacon_interval * skip);
+
+ mps_dbg(sta->sdata, "updating %pM next TBTT in %dus (%lldus awake)\n",
+ sta->sta.addr, nexttbtt_interval,
+ (long long) tsf_local - sta->nexttbtt_tsf);
+
+ sta->nexttbtt_tsf = tsf_local + nexttbtt_interval;
+ sta->nexttbtt_jiffies = jiffies + usecs_to_jiffies(nexttbtt_interval);
+
+ mod_timer(&sta->nexttbtt_timer, sta->nexttbtt_jiffies +
+ usecs_to_jiffies(BEACON_TIMEOUT));
+}
+
+/**
+ * ieee80211_mps_sta_tbtt_update - update peer beacon wakeup schedule
+ *
+ * @sta: mesh STA
+ * @mgmt: beacon frame
+ * @tim: TIM IE of beacon frame
+ * @tsf_local: current HW TSF
+ */
+void ieee80211_mps_sta_tbtt_update(struct sta_info *sta,
+ struct ieee80211_mgmt *mgmt,
+ struct ieee80211_tim_ie *tim,
+ u64 tsf_local)
+{
+ struct ieee80211_sub_if_data *sdata = sta->sdata;
+
+ if (!sdata->local->mps_enabled ||
+ sta->plink_state != NL80211_PLINK_ESTAB)
+ return;
+
+ sta->beacon_interval = le16_to_cpu(mgmt->u.beacon.beacon_int) * 1024;
+ /* pending multicasts after DTIM beacon? TODO reset after RX */
+ if (tim->bitmap_ctrl & 0x01)
+ set_sta_flag(sta, WLAN_STA_MPS_WAIT_FOR_CAB);
+ else
+ clear_sta_flag(sta, WLAN_STA_MPS_WAIT_FOR_CAB);
+
+ mps_sta_nexttbtt_calc(sta, tim, tsf_local);
+
+ mps_queue_work(sdata, MESH_WORK_PS_DOZE);
+}
+
+/**
+ * ieee80211_mps_sta_tbtt_timeout - timer callback for missed peer beacons
+ */
+void ieee80211_mps_sta_tbtt_timeout(unsigned long data)
+{
+ struct sta_info *sta = (void *)data;
+
+ rcu_read_lock();
+ sta->nexttbtt_tsf += sta->beacon_interval;
+ sta->nexttbtt_jiffies += usecs_to_jiffies(sta->beacon_interval);
+
+ mps_dbg(sta->sdata, "beacon miss %pM\n", sta->sta.addr);
+ mps_queue_work(sta->sdata, MESH_WORK_PS_DOZE);
+ rcu_read_unlock();
+}
+
+/**
+ * ieee80211_mps_awake_window_start - start Awake Window on SWBA
+ *
+ * @sdata: local mesh subif
+ */
+void ieee80211_mps_awake_window_start(struct ieee80211_sub_if_data *sdata)
+{
+ struct ieee80211_if_mesh *ifmsh = &sdata->u.mesh;
+
+ if (!sdata->local->mps_enabled)
+ return;
+
+ mod_timer(&ifmsh->awake_window_end_timer, jiffies + usecs_to_jiffies(
+ ifmsh->mshcfg.dot11MeshAwakeWindowDuration * 1024));
+
+ mps_dbg(sdata, "awake window start (%dTU)\n",
+ ifmsh->mshcfg.dot11MeshAwakeWindowDuration);
+ mps_queue_work(sdata, MESH_WORK_PS_WAKEUP);
+}
+
+/**
+ * ieee80211_mps_awake_window_end - timer callback for end of Awake Window
+ */
+void ieee80211_mps_awake_window_end(unsigned long data)
+{
+ struct ieee80211_sub_if_data *sdata = (void *) data;
+
+ if (!sdata->local->mps_enabled)
+ return;
+
+ mps_dbg(sdata, "awake window end\n");
+ mps_queue_work(sdata, MESH_WORK_PS_DOZE);
+}
+
+static bool mps_doze_check_vif(struct ieee80211_local *local)
+{
+ struct ieee80211_sub_if_data *sdata;
+ bool allow = true;
+
+ mutex_lock(&local->iflist_mtx);
+ list_for_each_entry(sdata, &local->interfaces, list) {
+ if (!ieee80211_sdata_running(sdata))
+ continue;
+
+ if (!ieee80211_vif_is_mesh(&sdata->vif) ||
+ timer_pending(&sdata->u.mesh.awake_window_end_timer)) {
+ allow = false;
+ break;
+ }
+ }
+ mutex_unlock(&local->iflist_mtx);
+
+ return allow;
+}
+
+static bool mps_doze_check_sta(struct ieee80211_local *local, u64 *nexttbtt)
+{
+ struct sta_info *sta;
+ bool allow = true;
+ u64 nexttbtt_min = ULLONG_MAX;
+
+ mutex_lock(&local->sta_mtx);
+ list_for_each_entry(sta, &local->sta_list, list) {
+ if (!ieee80211_vif_is_mesh(&sta->sdata->vif) ||
+ !ieee80211_sdata_running(sta->sdata) ||
+ sta->plink_state != NL80211_PLINK_ESTAB) {
+ continue;
+ } else if (test_sta_flag(sta, WLAN_STA_MPS_WAIT_FOR_CAB) ||
+ test_sta_flag(sta, WLAN_STA_MPSP_OWNER) ||
+ test_sta_flag(sta, WLAN_STA_MPSP_RECIPIENT) ||
+ time_in_range(jiffies, sta->nexttbtt_jiffies,
+ sta->nexttbtt_jiffies +
+ usecs_to_jiffies(BEACON_TIMEOUT))) {
+ allow = false;
+ break;
+ } else if (sta->nexttbtt_tsf < nexttbtt_min) {
+ nexttbtt_min = sta->nexttbtt_tsf;
+ }
+ }
+ mutex_unlock(&local->sta_mtx);
+
+ if (nexttbtt_min != ULLONG_MAX)
+ *nexttbtt = nexttbtt_min;
+
+ return allow;
+}
+
+/**
+ * ieee80211_mps_doze - check conditions and trigger radio doze state
+ *
+ * @local: local interface data
+ */
+void ieee80211_mps_doze(struct ieee80211_local *local)
+{
+ u64 nexttbtt = 0;
+ struct sta_info *sta;
+
+ if (!local->mps_enabled ||
+ !mps_doze_check_vif(local) ||
+ !mps_doze_check_sta(local, &nexttbtt))
+ return;
+
+ if (local->mps_ops)
+ local->mps_ops->hw_doze(&local->hw, nexttbtt);
+}
+
+/**
+ * ieee80211_mps_wakeup - trigger radio wakeup immediately
+ *
+ * @local: local interface data
+ */
+void ieee80211_mps_wakeup(struct ieee80211_local *local)
+{
+ if (local->mps_ops)
+ local->mps_ops->hw_wakeup(&local->hw);
+}
+
+int ieee80211_mps_init(struct ieee80211_hw *hw,
+ const struct ieee80211_mps_ops *ops)
+{
+ struct ieee80211_local *local = hw_to_local(hw);
+
+ local->mps_ops = ops;
+ if (!ops)
+ local->mps_enabled = false;
+
+ return 0;
+}
+EXPORT_SYMBOL(ieee80211_mps_init);
diff --git a/net/mac80211/sta_info.c b/net/mac80211/sta_info.c
index f920154..2905f2a 100644
--- a/net/mac80211/sta_info.c
+++ b/net/mac80211/sta_info.c
@@ -142,6 +142,7 @@ static void cleanup_single_sta(struct sta_info *sta)
mesh_accept_plinks_update(sdata);
mesh_plink_deactivate(sta);
del_timer_sync(&sta->plink_timer);
+ del_timer_sync(&sta->nexttbtt_timer);
}
#endif

@@ -385,6 +386,8 @@ struct sta_info *sta_info_alloc(struct ieee80211_sub_if_data *sdata,
#ifdef CONFIG_MAC80211_MESH
sta->plink_state = NL80211_PLINK_LISTEN;
init_timer(&sta->plink_timer);
+ setup_timer(&sta->nexttbtt_timer, ieee80211_mps_sta_tbtt_timeout,
+ (unsigned long) sta);
#endif

return sta;
diff --git a/net/mac80211/sta_info.h b/net/mac80211/sta_info.h
index 5a1deba..624d32a 100644
--- a/net/mac80211/sta_info.h
+++ b/net/mac80211/sta_info.h
@@ -58,6 +58,7 @@
* @WLAN_STA_TOFFSET_KNOWN: toffset calculated for this station is valid.
* @WLAN_STA_MPSP_OWNER: local STA is owner of a mesh Peer Service Period.
* @WLAN_STA_MPSP_RECIPIENT: local STA is recipient of a MPSP.
+ * @WLAN_STA_MPS_WAIT_FOR_CAB: multicast frames from this STA are imminent.
*/
enum ieee80211_sta_info_flags {
WLAN_STA_AUTH,
@@ -82,6 +83,7 @@ enum ieee80211_sta_info_flags {
WLAN_STA_TOFFSET_KNOWN,
WLAN_STA_MPSP_OWNER,
WLAN_STA_MPSP_RECIPIENT,
+ WLAN_STA_MPS_WAIT_FOR_CAB,
};

#define ADDBA_RESP_INTERVAL HZ
@@ -289,6 +291,10 @@ struct sta_ampdu_mlme {
* @local_pm: local link-specific power save mode
* @peer_pm: peer-specific power save mode towards local STA
* @nonpeer_pm: STA power save mode towards non-peer neighbors
+ * @beacon_interval: beacon interval of neighbor STA (in us)
+ * @nexttbtt_tsf: next TBTT in local TSF units
+ * @nexttbtt_jiffies: next TBTT in jiffies units
+ * @nexttbtt_timer: timeout for missed beacons
* @debugfs: debug filesystem info
* @dead: set to true when sta is unlinked
* @uploaded: set to true when sta is uploaded to the driver
@@ -390,6 +396,10 @@ struct sta_info {
enum nl80211_mesh_power_mode local_pm;
enum nl80211_mesh_power_mode peer_pm;
enum nl80211_mesh_power_mode nonpeer_pm;
+ u32 beacon_interval;
+ u64 nexttbtt_tsf;
+ unsigned long nexttbtt_jiffies;
+ struct timer_list nexttbtt_timer;
#endif

#ifdef CONFIG_MAC80211_DEBUGFS
diff --git a/net/mac80211/tx.c b/net/mac80211/tx.c
index 75ae941..4ad45f0 100644
--- a/net/mac80211/tx.c
+++ b/net/mac80211/tx.c
@@ -2495,6 +2495,8 @@ struct sk_buff *ieee80211_beacon_get_tim(struct ieee80211_hw *hw,
pr_err("o11s: couldn't add ies!\n");
goto out;
}
+
+ ieee80211_mps_awake_window_start(sdata);
} else {
WARN_ON(1);
goto out;
--
1.7.9.5


2013-02-13 14:59:10

by Johannes Berg

[permalink] [raw]
Subject: Re: [RFCv2 2/3] mac80211: mesh power save doze scheduling

On Mon, 2013-02-11 at 13:03 +0100, Marco Porsch wrote:
> On 02/08/2013 10:57 PM, Johannes Berg wrote:
> > On Fri, 2013-02-08 at 11:09 +0100, Marco Porsch wrote:
> >
> >>>> For mesh Awake Windows wakeup on SWBA (beacon_get_tim) and start
> >>>> a timer which triggers a doze call on expiry.
> >>>
> >>> That seems questionable -- drivers are not required to request each
> >>> beacon. I know you only want to make it work on ath9k, but I don't think
> >>> "stretching" the API, without even documenting it, is a good idea.
> >>
> >> Currently, we already use ieee80211_beacon_get_tim as time reference for
> >> mesh sync's adjust_tbtt. And, as far as I know, all mesh-capable drivers
> >> use the call for each and every beacon.
> >
> > Oops, why did I miss that before? :-)
> >
> >> So what would you recommend: keep using beacon_get and adding
> >> documentation - or - creating an exported callback for awake_window_start?
> >
> > I guess you could add it... However, I don't really fully understand.
> > There's no guarantee that fetching the beacon is done anywhere close to
> > TBTT? Or does ath9k happen to do it just after TXing a beacon? You're
> > encoding quite a lot of ath9k-specific assumptions here it seems?
>
> I think the assumption is currently correct for ath5k, ath9k, ath9k_htc,
> carl9170 and rt2800 (that's as far as I checked). All of these fetch a
> beacon on SWBA/PRETBTT interrupt (more or less) immediately before TBTT.

It's still pretty bad to make that assumption implicitly -- I think you
should at least document it as a big todo item :)

johannes