WARP Project Forums - Wireless Open-Access Research Platform

You are not logged in.

#1 2015-Mar-01 17:17:27

multiwarp
Member
Registered: 2014-Apr-15
Posts: 47

Use WARPLAB to observe 802.11 ref design constellations?

Hi,

I was under the impression that you guys are using WARPLAB to debug waveforms in 802.11 reference design. (read in a previous post) Could you share with me how to do that? Example wl_example_siso_spectrogram.m shows a spectrogram, not on a symbol by symbol basis. example, wl_example_siso_ofdm_txrx.m, creates its own traffic, is it fully compatible with 802.11 reference design traffic? How to modify it so that it can monitor a channel and extract the real packet and plot all the 6 plots of that packet?

Offline

 

#2 2015-Mar-01 19:27:42

multiwarp
Member
Registered: 2014-Apr-15
Posts: 47

Re: Use WARPLAB to observe 802.11 ref design constellations?

A follow up question: what is the accuracy of the ethernet trigger in WARPLAB examples, such as wl_example_siso_spectrogram.m and wl_example_siso_ofdm_txrx.m

Offline

 

#3 2015-Mar-02 11:21:57

murphpo
Administrator
From: Mango Communications
Registered: 2006-Jul-03
Posts: 5159

Re: Use WARPLAB to observe 802.11 ref design constellations?

We do not have an 802.11 receiver implementation for WARPLab. The WARPLab OFDM example waveform is similar to 802.11, and that example would be a good starting point for building a full receiver in m.

We have used WARPLab to measure EVM from our real-time 802.11 transmitter. Our script for this is based on the OFDM example, updated to use the 802.11-specified pilot tone pattern and scrambling sequence. This script does not implement any processing beyond equalization and EVM calculation (no demod, de-interleave, decode or de-scrambling). The full script is copied below. Please understand this is not an official WARPLab example. I'm not even sure it runs in WARPLab 7.5 as-is (we last used it with WL 7.4). But this should be helpful in adapting the official OFDM example to your application.

Code:

CHANNEL = 10;

%Waveform params
INTERP_RATE = 2;        %Interpolation rate (1 or 2)

%OFDM params
sc_ind_pilots = 1+[7 21 64-21 64-7];
sc_ind_data = [2:7 9:21 23:27 39:43 45:57 59:64];
N_SC = 64;          %Number of subcarriers
CP_LEN = 16;        %Cyclic prefix length
N_PYLD_SYMS = 40;

%Rx processing params
FFT_OFFSET = 4;     %Number of CP samples to use in FFT (on average)
LTS_CORR_THRESH = 0.8;  %Normalized threshold for LTS correlation
USE_PILOT_TONES = 1;    %Enabel phase error correction
DECIMATE_RATE = INTERP_RATE;

%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% Set up the WARPLab experiment
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

USE_AGC = false;

%Create a vector of node objects
nodes = wl_initNodes(1,1);

%Create a UDP broadcast trigger and tell each node to be ready for it
eth_trig = wl_trigger_eth_udp_broadcast;
wl_triggerManagerCmd(nodes,'add_ethernet_trigger',[eth_trig]);

%Read Trigger IDs into workspace
[T_IN_ETH,T_IN_ENERGY,T_IN_AGCDONE,T_IN_REG,T_IN_D0,T_IN_D1,T_IN_D2,T_IN_D3] =  wl_getTriggerInputIDs(nodes(1));
[T_OUT_BASEBAND, T_OUT_AGC, T_OUT_D0, T_OUT_D1, T_OUT_D2, T_OUT_D3] = wl_getTriggerOutputIDs(nodes(1));

%For the receive node, we will allow debug3 (mapped to pin 15 on the
%debug header) to trigger the buffer baseband, and the AGC
nodes(1).wl_triggerManagerCmd('output_config_input_selection',[T_OUT_BASEBAND,T_OUT_AGC],[T_IN_D3]);

%For the receive node, we enable the debounce circuity on the debug 3 input
%to deal with the fact that the signal may be noisy.
nodes(1).wl_triggerManagerCmd('input_config_debounce_mode',[T_IN_D3],'enable'); 


%Get IDs for the interfaces on the boards. Since this example assumes each
%board has the same interface capabilities, we only need to get the IDs
%from one of the boards
[RFA,RFB] = wl_getInterfaceIDs(nodes(1));


%Get IDs for the interfaces on the boards. Since this example assumes each
%board has the same interface capabilities, we only need to get the IDs
%from one of the boards
[RFA,RFB] = wl_getInterfaceIDs(nodes(1));

%Set up the interface for the experiment
wl_interfaceCmd(nodes,'RF_ALL','channel',2.4,CHANNEL);

if(USE_AGC)
    wl_interfaceCmd(nodes,'RF_ALL','rx_gain_mode','automatic');
    wl_basebandCmd(nodes,'agc_target',-10);
    wl_basebandCmd(nodes,'agc_trig_delay', 511);
else
    wl_interfaceCmd(nodes,'RF_ALL','rx_gain_mode','manual');
    RxGainRF = 2; %2 %Rx RF Gain in [1:3]
    RxGainBB = 12; %12 %Rx Baseband Gain in [0:31]
    wl_interfaceCmd(nodes,'RF_ALL','rx_gains',RxGainRF,RxGainBB);
end

wl_interfaceCmd(nodes, RF_RX,'rx_lpf_corn_freq',1);

SAMP_FREQ = wl_basebandCmd(nodes(1),'tx_buff_clk_freq'); 
node_rx = nodes(1);
RF_RX = RFA;

%Define a halfband 2x interp filter response
interp_filt2 = zeros(1,43);
interp_filt2([1 3 5 7 9 11 13 15 17 19 21]) = [12 -32 72 -140 252 -422 682 -1086 1778 -3284 10364];
interp_filt2([23 25 27 29 31 33 35 37 39 41 43]) = interp_filt2(fliplr([1 3 5 7 9 11 13 15 17 19 21]));
interp_filt2(22) = 16384;
interp_filt2 = interp_filt2./max(abs(interp_filt2));

%% Define the preamble
sts_f = zeros(1,64);
sts_f(1:27) = [0 0 0 0 -1-1i 0 0 0 -1-1i 0 0 0 1+1i 0 0 0 1+1i 0 0 0 1+1i 0 0 0 1+1i 0 0];
sts_f(39:64) = [0 0 1+1i 0 0 0 -1-1i 0 0 0 1+1i 0 0 0 -1-1i 0 0 0 -1-1i 0 0 0 1+1i 0 0 0];
sts_t = ifft(sqrt(13/6).*sts_f, 64);
sts_t = sts_t(1:16);

%LTS for CFO and channel estimation
lts_f = [0 1 -1 -1 1 1 -1 1 -1 1 -1 -1 -1 -1 -1 1 1 -1 -1 1 -1 1 -1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 1 1 -1 -1 1 1 -1 1 -1 1 1 1 1 1 1 -1 -1 1 1 -1 1 -1 1 1 1 1];
lts_t = ifft(lts_f, 64);

%Use 30 copies of the 16-sample STS for extra AGC settling margin
preamble = [repmat(sts_t, 1, 30)  lts_t(33:64) lts_t lts_t];

%% WL Rx
wl_interfaceCmd(node_rx,RF_RX,'rx_en');

%Enable the Tx and Rx buffers
wl_basebandCmd(node_rx,RF_RX,'rx_buff_en');

%Trigger the Tx/Rx cycle at both nodes
%eth_trig.send();

%Retrieve the received waveform from the Rx node
rx_vec_air = wl_basebandCmd(node_rx,[RF_RX],'read_IQ', 0,  node_rx.baseband.rxIQLen);
rx_vec_air = rx_vec_air(:).';

%Disable the Tx/Rx radios and buffers
wl_basebandCmd(nodes,'RF_ALL','tx_rx_buff_dis');
wl_interfaceCmd(nodes,'RF_ALL','tx_rx_dis');

%%
pilot_scrambler_lfsr = [1 1 1 1 1 1 1];
pilot_scrambling_seq = zeros(1,N_PYLD_SYMS);
for ii=1:N_PYLD_SYMS
    x = xor(pilot_scrambler_lfsr(4), pilot_scrambler_lfsr(7));
    pilot_scrambling_seq(ii) = x;
    pilot_scrambler_lfsr = [x pilot_scrambler_lfsr(1:6)];
end
pilot_scrambling_seq = -(2*pilot_scrambling_seq)+1;
pilot_scrambling_mat = repmat(pilot_scrambling_seq, 4, 1);
pilot_scrambling_mat(2,:) = pilot_scrambling_mat(2,:) * -1;


% Decimate
if(DECIMATE_RATE == 1)
    raw_rx_dec = rx_vec_air;
elseif(DECIMATE_RATE == 2)  
    raw_rx_dec = filter(interp_filt2, 1, rx_vec_air);
    raw_rx_dec = raw_rx_dec(1:2:end);
end

% Correlate for LTS

%Complex cross correlation of Rx waveform with time-domain LTS 
lts_corr = abs(conv(conj(fliplr(lts_t)), sign(raw_rx_dec)));

%Skip early and late samples
lts_corr = lts_corr(32:end-32);

%Find all correlation peaks
lts_peaks = find(lts_corr > LTS_CORR_THRESH*max(lts_corr));

%Select best candidate correlation peak as LTS-payload boundary
[LTS1, LTS2] = meshgrid(lts_peaks,lts_peaks);
[lts_second_peak_index,y] = find(LTS2-LTS1 == length(lts_t));

%Punt if no valid correlation peak was found
if(isempty(lts_second_peak_index))
    fprintf('No LTS Correlation Peaks Found!\n');
    return;
end

%Set the sample indices of the payload symbols and preamble
payload_ind = lts_peaks(max(lts_second_peak_index))+32;
lts_ind = payload_ind-160;

%

raw_rx_dec = raw_rx_dec(:);

%Extract LTS (not yet CFO corrected)
rx_lts = raw_rx_dec(lts_ind : lts_ind+159);
rx_lts1 = rx_lts(-64+-FFT_OFFSET + [97:160]);
rx_lts2 = rx_lts(-FFT_OFFSET + [97:160]);

%Calculate coarse CFO est
rx_cfo_est_lts = mean(unwrap(angle(rx_lts1 .* conj(rx_lts2))));
rx_cfo_est_lts = rx_cfo_est_lts/(2*pi*64);
rx_cfo_corr_t = exp(1i*2*pi*rx_cfo_est_lts*[0:length(raw_rx_dec)-1]);

%Apply CFO correction to raw Rx waveform
rx_dec_cfo_corr = raw_rx_dec .* rx_cfo_corr_t.';

%Re-extract LTS for H est
rx_lts = rx_dec_cfo_corr(lts_ind : lts_ind+159);
rx_lts1 = rx_lts(-64+-FFT_OFFSET + [97:160]);
rx_lts2 = rx_lts(-FFT_OFFSET + [97:160]);

rx_lts1_f = fft(rx_lts1);
rx_lts2_f = fft(rx_lts2);

%Calculate H est
rx_H_est = lts_f.' .* (rx_lts1_f + rx_lts2_f)/2;


%
payload_vec = rx_dec_cfo_corr(payload_ind : payload_ind+N_PYLD_SYMS*80-1);

payload_mat = reshape(payload_vec, 80, N_PYLD_SYMS);
payload_mat_noCP = payload_mat(CP_LEN-FFT_OFFSET+[1:64], :);

syms_f_mat = (fft(payload_mat_noCP, 64, 1));
syms_eq_mat = syms_f_mat ./ repmat(rx_H_est, 1, size(syms_f_mat, 2));

%Extract the pilots and calculate per-symbol phase error
pilots_f_mat = syms_eq_mat(sc_ind_pilots, :);
pilots_unscrambled = pilots_f_mat.*pilot_scrambling_mat;

pilot_phase_err = unwrap(angle(mean(pilots_unscrambled)));
pilot_phase_corr = repmat(exp(-1i*pilot_phase_err), 64, 1);
%pilot_phase_corr = repmat(exp(-1i*0*pilot_phase_err), 64, 1);


%Apply the pilot phase correction per symbol
syms_eq_pc_mat = syms_eq_mat .* pilot_phase_corr;
payload_syms_mat = syms_eq_pc_mat(sc_ind_data, :);

%Strip off the SIGNAL field

payload_syms_mat = payload_syms_mat(:,2:end);

sym_bpsk =  [-1, 1];
sym_qpsk = [-1.0000 + 1.0000i,  -1.0000 - 1.0000i,   1.0000 + 1.0000i,   1.0000 - 1.0000i];
sym_qam16 = [-3.0000 + 3.0000i,  -3.0000 + 1.0000i,  -3.0000 - 1.0000i,  -3.0000 - 3.0000i, ...
             -1.0000 + 3.0000i,  -1.0000 + 1.0000i,  -1.0000 - 1.0000i,  -1.0000 - 3.0000i, ...
             1.0000 + 3.0000i,  1.0000 + 1.0000i,   1.0000 - 1.0000i,   1.0000 - 3.0000i, ...
             3.0000 + 3.0000i,   3.0000 + 1.0000i,   3.0000 - 1.0000i,   3.0000 - 3.0000i];
sym_qam64 = [-7.0000 + 7.0000i,  -7.0000 + 5.0000i,  -7.0000 + 3.0000i,  -7.0000 + 1.0000i, ...
             -7.0000 - 1.0000i,  -7.0000 - 3.0000i,  -7.0000 - 5.0000i,  -7.0000 - 7.0000i, ...
             -5.0000 + 7.0000i,  -5.0000 + 5.0000i,  -5.0000 + 3.0000i,  -5.0000 + 1.0000i, ...
             -5.0000 - 1.0000i,  -5.0000 - 3.0000i,  -5.0000 - 5.0000i,  -5.0000 - 7.0000i, ...
             -3.0000 + 7.0000i,  -3.0000 + 5.0000i,  -3.0000 + 3.0000i,  -3.0000 + 1.0000i, ...
             -3.0000 - 1.0000i,  -3.0000 - 3.0000i,  -3.0000 - 5.0000i,  -3.0000 - 7.0000i, ...
             -1.0000 + 7.0000i,  -1.0000 + 5.0000i,  -1.0000 + 3.0000i,  -1.0000 + 1.0000i, ...
             -1.0000 - 1.0000i,  -1.0000 - 3.0000i,  -1.0000 - 5.0000i,  -1.0000 - 7.0000i, ...
             1.0000 + 7.0000i,   1.0000 + 5.0000i,   1.0000 + 3.0000i,   1.0000 + 1.0000i, ...
             1.0000 - 1.0000i,   1.0000 - 3.0000i,   1.0000 - 5.0000i,   1.0000 - 7.0000i, ...
             3.0000 + 7.0000i,   3.0000 + 5.0000i,   3.0000 + 3.0000i,   3.0000 + 1.0000i, ...
             3.0000 - 1.0000i,   3.0000 - 3.0000i,   3.0000 - 5.0000i,   3.0000 - 7.0000i, ...
             5.0000 + 7.0000i,   5.0000 + 5.0000i,   5.0000 + 3.0000i,   5.0000 + 1.0000i, ...
             5.0000 - 1.0000i,   5.0000 - 3.0000i,   5.0000 - 5.0000i,   5.0000 - 7.0000i, ...
             7.0000 + 7.0000i,   7.0000 + 5.0000i,   7.0000 + 3.0000i,   7.0000 + 1.0000i, ...
             7.0000 - 1.0000i,   7.0000 - 3.0000i,   7.0000 - 5.0000i,   7.0000 - 7.0000i];
         
%Normalize the constellations to average symbol power;
%bpsk_scale = mean(abs(sym_bpsk));
%qpsk_scale = mean(abs(sym_qpsk));
%qam_16_scale = mean(abs(sym_qam16));
%qam_64_scale = mean(abs(sym_qam64));

bpsk_scale = 1;
qpsk_scale = sqrt(2);
qam_16_scale = sqrt(10);
qam_64_scale = sqrt(42);

sym_bpsk_norm = sym_bpsk / bpsk_scale;
sym_qpsk_norm = sym_qpsk / qpsk_scale;
sym_qam16_norm = sym_qam16 / qam_16_scale;
sym_qam64_norm = sym_qam64 / qam_64_scale;

MODULATION_ORDER = 64;
switch(MODULATION_ORDER)
    case 2
        ref_syms = sym_bpsk_norm;
    case 4   
        ref_syms = sym_qpsk_norm;
    case 16
        ref_syms = sym_qam16_norm;
    case 64
        ref_syms = sym_qam64_norm;                
end



%Simulation rx_syms
rx_syms = payload_syms_mat(:);


figure(1);clf;
plot(rx_syms,'.')
hold on
plot(ref_syms,'or','LineWidth',2)
hold off
axis square

rx_syms_mat = repmat(rx_syms(:),1,length(ref_syms));
ref_syms_mat = repmat(ref_syms, length(rx_syms), 1);

error_mat = (rx_syms_mat - ref_syms_mat);

error_vec = min(error_mat,[],2);



evm_lin = mean(abs(error_vec));

figure(1);
title(sprintf('EVM = %f%%, %fdBm', 100*evm_lin, 20*log10(evm_lin)))

Offline

 

#4 2015-Mar-02 11:24:39

murphpo
Administrator
From: Mango Communications
Registered: 2006-Jul-03
Posts: 5159

Re: Use WARPLAB to observe 802.11 ref design constellations?

A follow up question: what is the accuracy of the ethernet trigger in WARPLAB examples, such as wl_example_siso_spectrogram.m and wl_example_siso_ofdm_txrx.m

You'll have to be more specific what you mean by accuracy here.

The WARPLab 7 design for WARP v3 monitors the Ethernet AXI stream interface in hardware, detecting trigger packets as the Ethernet PHY delivers the bytes to the FPGA. The timing of Ethernet packet reception to trigger assertion is deterministic. However the timing of Ethernet packet reception is determined by your PC, NIC, switch and cabling. These components may cause noticeable jitter across trials and across nodes. You can measure the timing of trigger assertion across nodes using the debug pins on the WARP v3 board.

Offline

 

#5 2015-Mar-03 20:28:54

multiwarp
Member
Registered: 2014-Apr-15
Posts: 47

Re: Use WARPLAB to observe 802.11 ref design constellations?

Hi,

This is the code I modified on top of the OFDM example.

Code:

%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
% wl_example_ofdm_monitor.m

% we want to listen to real 802.11 packets, and plot the 6 plots of it
% such as constellations
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
while 1
    clear

    % Params:
    USE_WARPLAB_TXRX        = 1;           % Enable WARPLab-in-the-loop (otherwise sim-only)
    WRITE_PNG_FILES         = 0;           % Enable writing plots to PNG

    % Waveform params
    N_OFDM_SYMS             = 40;         % Number of OFDM symbols
    MOD_ORDER               = 16;          % Modulation order (2/4/16 = BSPK/QPSK/16-QAM)
    TX_SCALE                = 1.0;         % Scale for Tx waveform ([0:1])
    INTERP_RATE             = 1;           % Interpolation rate (1 or 2)

    % OFDM params
    SC_IND_PILOTS           = [8 22 44 58];                           % Pilot subcarrier indices
    SC_IND_DATA             = [2:7 9:21 23:27 39:43 45:57 59:64];     % Data subcarrier indices
    N_SC                    = 64;                                     % Number of subcarriers
    CP_LEN                  = 16;                                     % Cyclic prefix length
    N_DATA_SYMS             = N_OFDM_SYMS * length(SC_IND_DATA);      % Number of data symbols (one per data-bearing subcarrier per OFDM symbol)

    % Rx processing params
    FFT_OFFSET              = 4;           % Number of CP samples to use in FFT (on average)
    LTS_CORR_THRESH         = 0.8;         % Normalized threshold for LTS correlation
    DO_APPLY_CFO_CORRECTION = 1;           % Enable CFO estimation/correction
    USE_PILOT_TONES         = 1;           % Enable phase error correction
    DECIMATE_RATE           = INTERP_RATE;

    % WARPLab experiment params
    USE_AGC                 = true;        % Use the AGC if running on WARP hardware
    MAX_TX_LEN              = 2^17;          % Maximum number of samples to use for this experiment

    % parameters extra
    CHANNEL                 = 14;           % Choose the channel we will receive on
    % NUM_SAMPLES             = 2^25;         % Number of samples to request
    NUM_SAMPLES             = 2^18;         % Number of samples to request




    %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
    % Set up the WARPLab experiment
    %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

    NUMNODES = 1;

    % Create a vector of node objects
    nodes = wl_initNodes(NUMNODES);

    % Create a UDP broadcast trigger and tell each node to be ready for it
    eth_trig = wl_trigger_eth_udp_broadcast;
    wl_triggerManagerCmd(nodes, 'add_ethernet_trigger', [eth_trig]);

    % Read Trigger IDs into workspace
    [T_IN_ETH_A, T_IN_ENERGY, T_IN_AGCDONE, T_IN_REG, T_IN_D0, T_IN_D1, T_IN_D2, T_IN_D3, T_IN_ETH_B] =  wl_getTriggerInputIDs(nodes(1));
    [T_OUT_BASEBAND, T_OUT_AGC, T_OUT_D0, T_OUT_D1, T_OUT_D2, T_OUT_D3] = wl_getTriggerOutputIDs(nodes(1));

    % For both nodes, we will allow Ethernet to trigger the buffer baseband and the AGC
    wl_triggerManagerCmd(nodes, 'output_config_input_selection', [T_OUT_BASEBAND, T_OUT_AGC], [T_IN_ETH_A, T_IN_REG]);

    % Set the trigger output delays. 
    nodes.wl_triggerManagerCmd('output_config_delay', [T_OUT_BASEBAND], 0);      
    nodes.wl_triggerManagerCmd('output_config_delay', [T_OUT_AGC], 3000);     %3000 ns delay before starting the AGC

    % Get IDs for the interfaces on the boards. Since this example assumes each
    % board has the same interface capabilities, we only need to get the IDs
    % from one of the boards
    [RFA,RFB] = wl_getInterfaceIDs(nodes(1));

    % Set up the interface for the experiment
    %     wl_interfaceCmd(nodes, 'RF_ALL', 'tx_gains', 3, 30);
    wl_interfaceCmd(nodes, 'RF_ALL', 'channel', 2.4, CHANNEL);

    if(USE_AGC)
        wl_interfaceCmd(nodes, 'RF_ALL', 'rx_gain_mode', 'automatic');
        wl_basebandCmd(nodes, 'agc_target', -13);
    else
        wl_interfaceCmd(nodes, 'RF_ALL', 'rx_gain_mode', 'manual');
        RxGainRF = 2;                  % Rx RF Gain in [1:3]
        RxGainBB = 17;                 % Rx Baseband Gain in [0:31]
        wl_interfaceCmd(nodes, 'RF_ALL', 'rx_gains', RxGainRF, RxGainBB);
    end

    % Set up the TX / RX nodes and RF interfaces    
    %     node_tx = nodes(1);
    node_rx = nodes;
    %     RF_TX   = RFA;
    RF_RX   = RFA;


    % Check the number of samples

    max_rx_samples = wl_basebandCmd(nodes, RF_RX, 'rx_buff_max_num_samples');
    maximum_buffer_len = max_rx_samples;
    TX_NUM_SAMPS = min(MAX_TX_LEN, maximum_buffer_len);
    NUM_SAMPLES = min(TX_NUM_SAMPS,NUM_SAMPLES);

    if ( strcmp( class(nodes.transport), 'wl_transport_eth_udp_mex' ) )
        if ( NUM_SAMPLES > nodes.baseband.MEX_TRANSPORT_MAX_IQ )
            fprintf('\nWARNING:  Requested %d samples.  Due to Matlab memory limitations, the mex transport only supports %d samples.', NUM_SAMPLES, node.baseband.MEX_TRANSPORT_MAX_IQ);
            fprintf('WARNING:  If your computer has enough physical memory, you can adjust this limit using node.baseband.MEX_TRANSPORT_MAX_IQ ');
            fprintf('WARNING:  up to a maximum of %d samples.\n\n', max_rx_samples);

            NUM_SAMPLES = nodes.baseband.MEX_TRANSPORT_MAX_IQ;
        end
    else 
        if ( NUM_SAMPLES > nodes.baseband.JAVA_TRANSPORT_MAX_IQ )
            fprintf('\nWARNING:  WARPLab by default only supports %d samples for the spectrogram\n', node.baseband.JAVA_TRANSPORT_MAX_IQ);
            fprintf('WARNING:  using the java transport.  Please use the MEX transport to increase the\n');
            fprintf('WARNING:  number of samples in the spectrogram.\n\n');

            NUM_SAMPLES = nodes.baseband.JAVA_TRANSPORT_MAX_IQ;
        end
    end

    if ( NUM_SAMPLES > max_rx_samples ) 
        fprintf('\nWARNING:  Requested %d samples.  Node only supports %d samples.\n\n', NUM_SAMPLES, max_rx_samples);

        NUM_SAMPLES = max_rx_samples;    
    end

    % Get parameters from the node
    SAMP_FREQ    = 40e6;
    TX_NUM_SAMPS = NUM_SAMPLES;

    % Set up the baseband for the experiment
    %     wl_basebandCmd(nodes, 'tx_delay', 0);
    %     wl_basebandCmd(nodes, 'tx_length', TX_NUM_SAMPS);      % Number of samples to send
    wl_basebandCmd(nodes, 'rx_length', NUM_SAMPLES);      % Number of samples to receive
    example_mode_string = 'hw';

    % Open up the transceiver's low-pass filter to its maximum bandwidth (36MHz)
    wl_interfaceCmd(nodes, RF_RX, 'rx_lpf_corn_freq', 3);

    %% Define a half-band 2x interpolation filter response
    interp_filt2 = zeros(1,43);
    interp_filt2([1 3 5 7 9 11 13 15 17 19 21]) = [12 -32 72 -140 252 -422 682 -1086 1778 -3284 10364];
    interp_filt2([23 25 27 29 31 33 35 37 39 41 43]) = interp_filt2(fliplr([1 3 5 7 9 11 13 15 17 19 21]));
    interp_filt2(22) = 16384;
    interp_filt2 = interp_filt2./max(abs(interp_filt2));

    % Define the preamble
    sts_f = zeros(1,64);
    sts_f(1:27) = [0 0 0 0 -1-1i 0 0 0 -1-1i 0 0 0 1+1i 0 0 0 1+1i 0 0 0 1+1i 0 0 0 1+1i 0 0];
    sts_f(39:64) = [0 0 1+1i 0 0 0 -1-1i 0 0 0 1+1i 0 0 0 -1-1i 0 0 0 -1-1i 0 0 0 1+1i 0 0 0];
    sts_t = ifft(sqrt(13/6).*sts_f, 64);
    sts_t = sts_t(1:16);

    % LTS for CFO and channel estimation
    lts_f = [0 1 -1 -1 1 1 -1 1 -1 1 -1 -1 -1 -1 -1 1 1 -1 -1 1 -1 1 -1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 1 1 -1 -1 1 1 -1 1 -1 1 1 1 1 1 1 -1 -1 1 1 -1 1 -1 1 1 1 1];
    lts_t = ifft(lts_f, 64);

    % Use 30 copies of the 16-sample STS for extra AGC settling margin
    preamble = [repmat(sts_t, 1, 30)  lts_t(33:64) lts_t lts_t];

    % Sanity check inputs
    if(INTERP_RATE*((N_OFDM_SYMS * (N_SC + CP_LEN)) + length(preamble)) > TX_NUM_SAMPS)
        fprintf('Too many OFDM symbols for TX_NUM_SAMPS!\n');
        fprintf('Reduce N_OFDM_SYMS to %d\n',  floor(( (TX_NUM_SAMPS/INTERP_RATE)-length(preamble) )/( N_SC + CP_LEN )) - 1);
        return;
    end

    %% Generate a payload (in this case just to get the constellation comparing point)
    tx_data = randi(MOD_ORDER, 1, N_DATA_SYMS) - 1;

    % Functions for data -> complex symbol mapping (avoids comm toolbox requirement for qammod)
    modvec_bpsk   =  (1/sqrt(2))  .* [-1 1];
    modvec_16qam  = (1/sqrt(10)) .* [-3 -1 +3 +1];

    mod_fcn_bpsk  = @(x) complex(modvec_bpsk(1+x),0);
    mod_fcn_qpsk  = @(x) complex(modvec_bpsk(1+bitshift(x, -1)), modvec_bpsk(1+mod(x, 2)));
    mod_fcn_16qam = @(x) complex(modvec_16qam(1+bitshift(x, -2)), modvec_16qam(1+mod(x,4)));

    % Map the data values on to complex symbols
    switch MOD_ORDER
        case 2         % BPSK
            tx_syms = arrayfun(mod_fcn_bpsk, tx_data);
        case 4         % QPSK
            tx_syms = arrayfun(mod_fcn_qpsk, tx_data);
        case 16        % 16-QAM
            tx_syms = arrayfun(mod_fcn_16qam, tx_data);      
        otherwise
            fprintf('Invalid MOD_ORDER (%d)!  Must be in [2, 4, 16]\n', MOD_ORDER);
            return;
    end

    % Reshape the symbol vector to a matrix with one column per OFDM symbol
    tx_syms_mat = reshape(tx_syms, length(SC_IND_DATA), N_OFDM_SYMS);



    % Define the pilot tones
    if(USE_PILOT_TONES)
        pilots = [1 1 -1 1].';
    else
        pilots = [0 0 0 0].';
    end

    % Repeat the pilots across all OFDM symbols
    pilots_mat = repmat(pilots, 1, N_OFDM_SYMS);
    % 
    % %% IFFT
    % 
    % % Construct the IFFT input matrix
    % ifft_in_mat = zeros(N_SC, N_OFDM_SYMS);
    % 
    % % Insert the data and pilot values; other subcarriers will remain at 0
    % ifft_in_mat(SC_IND_DATA, :)   = tx_syms_mat;
    % ifft_in_mat(SC_IND_PILOTS, :) = pilots_mat;
    % 
    % %Perform the IFFT
    % tx_payload_mat = ifft(ifft_in_mat, N_SC, 1);
    % 
    % % Insert the cyclic prefix
    % if(CP_LEN > 0)
    %     tx_cp = tx_payload_mat((end-CP_LEN+1 : end), :);
    %     tx_payload_mat = [tx_cp; tx_payload_mat];
    % end
    % 
    % % Reshape to a vector
    % tx_payload_vec = reshape(tx_payload_mat, 1, numel(tx_payload_mat));
    % 
    % % Construct the full time-domain OFDM waveform
    % tx_vec = [preamble tx_payload_vec];
    % 
    % % Pad with zeros for transmission
    % tx_vec_padded = [tx_vec zeros(1,(TX_NUM_SAMPS/INTERP_RATE)-length(tx_vec))];
    % 
    % %% Interpolate
    % if(INTERP_RATE == 1)
    %     tx_vec_air = tx_vec_padded;
    % elseif(INTERP_RATE == 2)
    %     tx_vec_2x = zeros(1, 2*numel(tx_vec_padded));
    %     tx_vec_2x(1:2:end) = tx_vec_padded;
    %     tx_vec_air = filter(interp_filt2, 1, tx_vec_2x);
    % end
    % 
    % % Scale the Tx vector
    % tx_vec_air = TX_SCALE .* tx_vec_air ./ max(abs(tx_vec_air));

    %% WARPLab Tx/Rx
    % Write the Tx waveform to the Tx node
    % wl_basebandCmd(node_tx,[RF_TX], 'write_IQ', tx_vec_air(:));

    % Enable the Tx and Rx radios
    % wl_interfaceCmd(node_tx,RF_TX, 'tx_en');
    wl_interfaceCmd(node_rx,RF_RX, 'rx_en');

    % Enable the Tx and Rx buffers
    % wl_basebandCmd(node_tx,RF_TX, 'tx_buff_en');
    wl_basebandCmd(node_rx,RF_RX, 'rx_buff_en');

    % Trigger the Tx/Rx cycle at both nodes
    eth_trig.send();

    % Pause for the samples to be processed at the node
    pause(TX_NUM_SAMPS * 1/(40e6));




    % Retrieve the received waveform from the Rx node
    rx_vec_air = wl_basebandCmd(node_rx,[RF_RX], 'read_IQ', 0, TX_NUM_SAMPS);  

    rx_vec_air = rx_vec_air(:).';

    % Disable the Tx/Rx radios and buffers
    wl_basebandCmd(nodes, 'RF_ALL', 'tx_rx_buff_dis');
    wl_interfaceCmd(nodes, 'RF_ALL', 'tx_rx_dis');

    %% Decimate
    if(DECIMATE_RATE == 1)
        raw_rx_dec = rx_vec_air;
    elseif(DECIMATE_RATE == 2)  
        raw_rx_dec = filter(interp_filt2, 1, rx_vec_air);
        raw_rx_dec = raw_rx_dec(1:2:end);
    end

    %% Correlate for LTS

    % Complex cross correlation of Rx waveform with time-domain LTS 
    lts_corr = abs(conv(conj(fliplr(lts_t)), sign(raw_rx_dec)));

    % Skip early and late samples
    lts_corr = lts_corr(32:end-32);

    % Find all correlation peaks
    lts_peaks = find(lts_corr > LTS_CORR_THRESH*max(lts_corr));

    % Select best candidate correlation peak as LTS-payload boundary
    [LTS1, LTS2] = meshgrid(lts_peaks,lts_peaks);
    [lts_second_peak_index,y] = find(LTS2-LTS1 == length(lts_t));

    % Stop if no valid correlation peak was found
    if(isempty(lts_second_peak_index))
        fprintf('No LTS Correlation Peaks Found!\n');
    %     return;
        continue;
    end

    % Set the sample indices of the payload symbols and preamble
    payload_ind = lts_peaks(max(lts_second_peak_index))+32;
    lts_ind = payload_ind-160;

    if(DO_APPLY_CFO_CORRECTION)
        %Extract LTS (not yet CFO corrected)
        rx_lts = raw_rx_dec(lts_ind : lts_ind+159);
        rx_lts1 = rx_lts(-64+-FFT_OFFSET + [97:160]);
        rx_lts2 = rx_lts(-FFT_OFFSET + [97:160]);

        %Calculate coarse CFO est
        rx_cfo_est_lts = mean(unwrap(angle(rx_lts1 .* conj(rx_lts2))));
        rx_cfo_est_lts = rx_cfo_est_lts/(2*pi*64);
    else
        rx_cfo_est_lts = 0;
    end

    % Apply CFO correction to raw Rx waveform
    rx_cfo_corr_t = exp(1i*2*pi*rx_cfo_est_lts*[0:length(raw_rx_dec)-1]);
    rx_dec_cfo_corr = raw_rx_dec .* rx_cfo_corr_t;

    % Re-extract LTS for channel estimate
    rx_lts = rx_dec_cfo_corr(lts_ind : lts_ind+159);
    rx_lts1 = rx_lts(-64+-FFT_OFFSET + [97:160]);
    rx_lts2 = rx_lts(-FFT_OFFSET + [97:160]);

    rx_lts1_f = fft(rx_lts1);
    rx_lts2_f = fft(rx_lts2);

    % Calculate channel estimate
    rx_H_est = lts_f .* (rx_lts1_f + rx_lts2_f)/2;

    %% Rx payload processing

    % Extract the payload samples (integral number of OFDM symbols following preamble)
    payload_vec = rx_dec_cfo_corr(payload_ind : payload_ind+N_OFDM_SYMS*(N_SC+CP_LEN)-1);
    payload_mat = reshape(payload_vec, (N_SC+CP_LEN), N_OFDM_SYMS);

    % Remove the cyclic prefix, keeping FFT_OFFSET samples of CP (on average)
    payload_mat_noCP = payload_mat(CP_LEN-FFT_OFFSET+[1:N_SC], :);

    % Take the FFT
    syms_f_mat = fft(payload_mat_noCP, N_SC, 1);

    % Equalize (zero-forcing, just divide by compled chan estimates)
    syms_eq_mat = syms_f_mat ./ repmat(rx_H_est.', 1, N_OFDM_SYMS);

    % Extract the pilots and calculate per-symbol phase error
    pilots_f_mat = syms_eq_mat(SC_IND_PILOTS, :);
    pilot_phase_err = angle(mean(pilots_f_mat.*pilots_mat));
    pilot_phase_corr = repmat(exp(-1i*pilot_phase_err), N_SC, 1);

    % Apply the pilot phase correction per symbol
    syms_eq_pc_mat = syms_eq_mat .* pilot_phase_corr;
    payload_syms_mat = syms_eq_pc_mat(SC_IND_DATA, :);

    %% Demodulate
    rx_syms = reshape(payload_syms_mat, 1, N_DATA_SYMS);

    demod_fcn_bpsk = @(x) double(real(x)>0);
    demod_fcn_qpsk = @(x) double(2*(real(x)>0) + 1*(imag(x)>0));
    demod_fcn_16qam = @(x) (8*(real(x)>0)) + (4*(abs(real(x))<0.6325)) + (2*(imag(x)>0)) + (1*(abs(imag(x))<0.6325));

    switch(MOD_ORDER)
        case 2         % BPSK
            rx_data = arrayfun(demod_fcn_bpsk, rx_syms);
        case 4         % QPSK
            rx_data = arrayfun(demod_fcn_qpsk, rx_syms);
        case 16        % 16-QAM
            rx_data = arrayfun(demod_fcn_16qam, rx_syms);    
    end

    % %% Calculate Rx stats
    % 
    % sym_errs = sum(tx_data ~= rx_data);
    % bit_errs = length(find(dec2bin(bitxor(tx_data, rx_data),8) == '1'));
    % rx_evm   = sqrt(sum((real(rx_syms) - real(tx_syms)).^2 + (imag(rx_syms) - imag(tx_syms)).^2)/(length(SC_IND_DATA) * N_OFDM_SYMS));
    % 
    % fprintf('\nResults:\n');
    % fprintf('Num Bytes:   %d\n', N_DATA_SYMS * log2(MOD_ORDER) / 8);
    % fprintf('Sym Errors:  %d (of %d total symbols)\n', sym_errs, N_DATA_SYMS);
    % fprintf('Bit Errors:  %d (of %d total bits)\n', bit_errs, N_DATA_SYMS * log2(MOD_ORDER));
    % fprintf('EVM:         %1.3f%%\n', rx_evm*100);
    % fprintf('LTS CFO Est: %3.2f kHz\n', rx_cfo_est_lts*(SAMP_FREQ/INTERP_RATE)*1e-3);
    % 

    %% Plot Results
    cf = 0;

    % % Tx signal
    % cf = cf + 1;
    % figure(cf); clf;
    % 
    % subplot(2,1,1);
    % plot(real(tx_vec_air), 'b');
    % axis([0 length(tx_vec_air) -TX_SCALE TX_SCALE])
    % grid on;
    % title('Tx Waveform (I)');
    % 
    % subplot(2,1,2);
    % plot(imag(tx_vec_air), 'r');
    % axis([0 length(tx_vec_air) -TX_SCALE TX_SCALE])
    % grid on;
    % title('Tx Waveform (Q)');
    % 
    % if(WRITE_PNG_FILES)
    %     print(gcf,sprintf('wl_ofdm_plots_%s_txIQ', example_mode_string), '-dpng', '-r96', '-painters')
    % end

    % Rx signal
    cf = cf + 1;
    figure(cf); clf;
    subplot(2,1,1);
    plot(real(rx_vec_air), 'b');
    axis([0 length(rx_vec_air) -TX_SCALE TX_SCALE])
    grid on;
    title('Rx Waveform (I)');

    subplot(2,1,2);
    plot(imag(rx_vec_air), 'r');
    axis([0 length(rx_vec_air) -TX_SCALE TX_SCALE])
    grid on;
    title('Rx Waveform (Q)');

    if(WRITE_PNG_FILES)
        print(gcf,sprintf('wl_ofdm_plots_%s_rxIQ', example_mode_string), '-dpng', '-r96', '-painters')
    end

    % Rx LTS correlation
    cf = cf + 1;
    figure(cf); clf;
    lts_to_plot = lts_corr(1:1000);
    plot(lts_to_plot, '.-b', 'LineWidth', 1);
    hold on;
    grid on;
    line([1 length(lts_to_plot)], LTS_CORR_THRESH*max(lts_to_plot)*[1 1], 'LineStyle', '--', 'Color', 'r', 'LineWidth', 2);
    title('LTS Correlation and Threshold')
    xlabel('Sample Index')

    if(WRITE_PNG_FILES)
        print(gcf,sprintf('wl_ofdm_plots_%s_ltsCorr', example_mode_string), '-dpng', '-r96', '-painters')
    end

    % Channel Estimates
    cf = cf + 1;

    rx_H_est_plot = repmat(complex(NaN,NaN),1,length(rx_H_est));
    rx_H_est_plot(SC_IND_DATA) = rx_H_est(SC_IND_DATA);
    rx_H_est_plot(SC_IND_PILOTS) = rx_H_est(SC_IND_PILOTS);

    x = (20/N_SC) * (-(N_SC/2):(N_SC/2 - 1));

    figure(cf); clf;
    subplot(2,1,1);
    stairs(x - (20/(2*N_SC)), fftshift(real(rx_H_est_plot)), 'b', 'LineWidth', 2);
    hold on
    stairs(x - (20/(2*N_SC)), fftshift(imag(rx_H_est_plot)), 'r', 'LineWidth', 2);
    hold off
    axis([min(x) max(x) -1.1*max(abs(rx_H_est_plot)) 1.1*max(abs(rx_H_est_plot))])
    grid on;
    title('Channel Estimates (I and Q)')

    subplot(2,1,2);
    bh = bar(x, fftshift(abs(rx_H_est_plot)),1,'LineWidth', 1);
    shading flat
    set(bh,'FaceColor',[0 0 1])
    axis([min(x) max(x) 0 1.1*max(abs(rx_H_est_plot))])
    grid on;
    title('Channel Estimates (Magnitude)')
    xlabel('Baseband Frequency (MHz)')

    if(WRITE_PNG_FILES)
        print(gcf,sprintf('wl_ofdm_plots_%s_chanEst', example_mode_string), '-dpng', '-r96', '-painters')
    end

    % Pilot phase error estimate
    cf = cf + 1;
    figure(cf); clf;
    plot(pilot_phase_err, 'b', 'LineWidth', 2);
    title('Phase Error Estimates')
    xlabel('OFDM Symbol Index')
    axis([1 N_OFDM_SYMS -3.2 3.2])
    grid on

    if(WRITE_PNG_FILES)
        print(gcf,sprintf('wl_ofdm_plots_%s_phaseError', example_mode_string), '-dpng', '-r96', '-painters')
    end

    % Symbol constellation
    cf = cf + 1;
    figure(cf); clf;

    plot(payload_syms_mat(:),'r.');
    axis square; axis(1.5*[-1 1 -1 1]);
    grid on;
    hold on;

    plot(tx_syms_mat(:),'bo');
    title('Tx and Rx Constellations')
    legend('Rx','Tx')

    if(WRITE_PNG_FILES)
        print(gcf,sprintf('wl_ofdm_plots_%s_constellations', example_mode_string), '-dpng', '-r96', '-painters')
    end
    break;
end;

Quite often, it gets "No LTS Correlation Peaks Found!" It seems not locking on the symbol very good. So I add a while loop, usually it will loop 4--10 times to find a lock-on. But from the correlation it's making sense at all. Am I missing something?

http://catnip.usc.edu/carma/signmap/1.png
http://catnip.usc.edu/carma/signmap/3.png
http://catnip.usc.edu/carma/signmap/4.png
http://catnip.usc.edu/carma/signmap/5.png

Offline

 

#6 2015-Mar-03 21:19:04

multiwarp
Member
Registered: 2014-Apr-15
Posts: 47

Re: Use WARPLAB to observe 802.11 ref design constellations?

http://catnip.usc.edu/carma/signmap/7.png

Offline

 

#7 2015-Mar-03 21:25:49

murphpo
Administrator
From: Mango Communications
Registered: 2006-Jul-03
Posts: 5159

Re: Use WARPLAB to observe 802.11 ref design constellations?

You will need to implement a better packet detection and synchronization scheme than the one in the OFDM example.

The WARPLab OFDM example is built for a 2-node setup where both Tx and Rx are controlled from a single script. Critically, the script knows the Tx node starts its transmission at approximately the same time the Rx node captures its waveform. Thus, there is no need for coarse packet detection or synchronization. This comes for "free" when Tx and Rx are triggered by the WARPLab script.

The LTS correlator establishes sample-level synchronization, but is not sufficient on its own to detect packets. In your waveform above the I/Q traces indicate you captured the tail end of one transmission and the very beginning of another. It is likely that this waveform has no OFDM preamble - there is nothing for the LTS correlator to find. The OFDM example uses a simple LTS correlation threshold technique of looking for 2 peaks higher than LTS_CORR_THRESH*(the highest LTS peak). This technique is not useful when the input waveform has no preamble.

Offline

 

#8 2015-Mar-03 21:27:21

murphpo
Administrator
From: Mango Communications
Registered: 2006-Jul-03
Posts: 5159

Re: Use WARPLAB to observe 802.11 ref design constellations?

One other factor to consider- many (way more than you might expect) 802.11 waveforms in real networks are transmitted at 1Mb/s using the DSSS waveform from the original 802.11 spec. This includes beacons, probe request/response, even some authentication packets. You can use Wireshark in monitor mode to observe these. The OFDM example will not receive DSSS waveforms.

Offline

 

#9 2015-Mar-03 22:28:31

multiwarp
Member
Registered: 2014-Apr-15
Posts: 47

Re: Use WARPLAB to observe 802.11 ref design constellations?

Thanks for quick reply. Does our 802.11 ref design use preamble though? Is it the same defined in WARPLAB examples? If I'm in a completely noise free space, would WARPLAB capture it?

Offline

 

#10 2015-Mar-03 23:07:24

multiwarp
Member
Registered: 2014-Apr-15
Posts: 47

Re: Use WARPLAB to observe 802.11 ref design constellations?

Hi Patrick,

I find this channel estimation funny.

Code:

% Calculate channel estimate
rx_H_est = lts_f .* (rx_lts1_f + rx_lts2_f)/2;

Shouldn't it be

Code:

(rx_lts1_f + rx_lts2_f)/2  / lts_f

Offline

 

#11 2015-Mar-04 09:49:19

murphpo
Administrator
From: Mango Communications
Registered: 2006-Jul-03
Posts: 5159

Re: Use WARPLAB to observe 802.11 ref design constellations?

Does our 802.11 ref design use preamble though? Is it the same defined in WARPLAB examples?

Yes- our 802.11 Reference Design PHY implementaiton uses the preamble specified in the standard. The WARPLab OFDM example uses a similar preamble. The OFDM example has extra repetitions of the short training symbols to handle trigger jitter. The OFDM example long training symbols are the same as 802.11.

If I'm in a completely noise free space, would WARPLAB capture it?

WARPLab captures samples when triggered- the WARPLab design has no idea whether the samples contain an OFDM preamble, DSSS preamble, noise, etc..

If the captured samples a full 802.11 OFDM transmission, your m code should be able to isolate the full packet and process it down to a constellation.

Offline

 

#12 2015-Mar-04 09:50:30

murphpo
Administrator
From: Mango Communications
Registered: 2006-Jul-03
Posts: 5159

Re: Use WARPLAB to observe 802.11 ref design constellations?

multiwarp wrote:

Hi Patrick,

I find this channel estimation funny.

Code:

% Calculate channel estimate
rx_H_est = lts_f .* (rx_lts1_f + rx_lts2_f)/2;

Shouldn't it be

Code:

(rx_lts1_f + rx_lts2_f)/2  / lts_f

In general you're right. But the training symbol is defined as BSPK symbols in the frequency domain (i.e. each subcarrier contains +1 or -1), so multiplying and dividing do the same thing, and multiplying is cheaper.

Offline

 

Board footer