Part of the WiROS Wifi sensing toolbox
ROS package providing utilities for CSI data correction and calculation of Angle-of-Arrival (AoA) from input CSI messages.
This package contains two nodes:
-
aoa_node takes in input CSI from the
/csi
topic and publishes 1d and 2d AoA/ToF profiles asProfile1d
andProfile2d
messages to/profile1d_raw
and/profile2d_raw
respectively -
correction_node applies compensation and corrects phase shifts in raw CSI data from
/csi_raw
, republishing the CSI and RSSI from incomingWifi
messages asCsi
andRssi
messages to/csi
and/rssi
These nodes support arbitrary (planar) antenna array configurations allowing for linear, square, etc. array shapes, though some algorithms assume a linear arrangement. algorithm.py is written in such a way that it is very easy to add new ones.
Note
Our experimentation was done on a Uniform Linear Array (ULA) of 4 antennas spaced 3 cm apart. The list [0, 2, 1, 3]
maps physical array element to CSI n_rx
dimension index. Antenna number zero is the origin, the +Y axis extends from it away from the other antennas, and the +X axis is oriented so the two follow the right hand rule. Angles of attack are measured going counterclockwise from the +X axis.
-
algo
: The algorithm to use. See the direction-finding algorithms section. -
theta_min
,theta_max
,theta_count
: the AoA values to search over. -
tau_min
,tau_max
,tau_count
: the ToF values to search over. -
profiles
: One of0
,1
,2
, or3
. The type of profile or profiles to publish.1
and2
are for 1d-only and 2d-only;3
is both. Defaults to3
. -
rx_position
: The position of the receiver antennas in the coordinate frame you wish to measure in. AoA is measured going counter-clockwise from the positive x-axis. Typically you would put the first antenna at the origin. More explanations as well as some example antenna array setups can be found in antennas.md. -
buffer_size
: The size of the circular buffer for CSI data. Not used by all algorithms. -
rate
: Target publishing rate. The processing is controlled by a timer running at this rate, and is separate from the rate at which data is published to/csi
.
-
algo
: The algorithm to use. See the correction algorithms section. -
rssi_threshold
: Only keep CSI for frames where RSSI is above this limit. Filters out poor-quality measurements. -
compensation_path
: Optional path to a compensation file. These are channel-specific files containing calibration values for the measured phase. Compensation files should be stored in the format{receiver IP}-{channel number}.npy
, e.g.192.168.1.1-36.npy
. This repo only supports using one channel's compensation file at a time.
In order to accurately measure AoA, we need the relative phase between different pairs of antennas. However, due to differing wire lengths as well as filter effects from the onboard RF circuitry, each RX chain will have a phase bias which varies per subcarrier and per channel. So in order to accurately measure AoA, these biases need to be measured and removed from incoming data. The necessary phases to remove these biases can then be passed in the comp
parameter and will be applied to incoming CSI by the ROS node.
The static compensation method provides very clean results but requires a 4-to-1 power splitter, 3 SMA 50-ohm terminators, about 55dB of attenuators, and a second AC86u.
The simplest way to measure the phase bias at the receiver is to ensure that the phase at each receiver is identical and measure the resulting phase. The idea is to ensure this is the case by injecting exactly the same signal to each receiver.
-
Connect the 4 receiver ports of the AC86u to the output of the power splitter. Ensure that you have the same length of cable between the board and each splitter port as you normally would between the board and each antenna.
-
Connect the attenuators to the input of the splitter, and one of the outputs of the other AC86u to the attenuators. Ideally you should terminate the other 3 antenna ports to cancel any crosstalk.
-
Start the csi_node at both the transmitter and receiver ends. The transmitter should have packet injection turned on and the receiver should set its MAC filter to the address the transmitter is injecting with.
-
Save the CSI data measured to a bag file, via
rosbag record /csi -O compensation_csi.bag
-
Use the rosbag processing script to create the compensation file:
rosrun wiros_processing generate_static_compensation.py BAG_PATH
Compensation files follow the naming convention {IP}-{chanspec}.npy
. NOTE: The above file conjugates the received CSI matrix.
CSI data has a lot of phase-related artifacts from processes and errors that might throw off direction-finding algorithms. Ma et. al. (2019) model the observed (unwrapped) CSI phase
Where
Note that most of these processing artifacts and errors cause phase shifts that vary linearly in frequency. The core idea behind the correction algorithms is to do linear regression on the phase of CSI data to extract the parameters. Below are some compensation algorithms.
This is the ToF sanitization algorithm (algorithm 1) from Kotaru et. al. (2015), rewritten to use notation consistent with the definitions above. This addresses STO, and also by the nature of the process ends up accounting for random packet delay.
The SpotFi correction method simplifies the model to
where
Then
Identical to the SpotFi compensation algorithm in concept, though the linear regression is performed with np.polyfit
, which uses the singular value decomposition instead of using the closed form of the least squares solution. The results have a different scale from the SpotFi method in our experimentation due to the fact that this method uses the absolute subcarrier frequencies instead of the differences between them.
The algorithm proposed by Ma et. al. (2019), which accounts for CSD
Stacking these into a block matrix system,
Then we can recover the parameters by solving the least-squares system
Here we will describe the functioning concepts of the direction-finding algorithms. For simplicity, the derivations here assume a linear antenna array and an OFDM signal on channel 155 with 80 MHz bandwidth, though the reasoning extends to arbitrary planar arrays and other OFDM channels and bandwidths.
We know the speed of light
Because each antenna is in a different location and the speed of light is finite, there is a small, direction-dependent phase delay
where
In addition to AoA, some methods leverage per-subcarrier phase delays due to differences in time of flight (ToF). Let
We can create another steering vector
Each method uses the
This 2D profile is published as a Profile2d
message to /profile2d
. To create the 1D profile Profile1d
to /profile1d
, we compute the single most likely ToF sample index
And then define
The specifics of each method are documented below. Note that the new_csi
given to the csi_callback
has shape (n_sub, n_rx, n_tx)
, so n_sub
is n_rx
is
Conventional beamforming but in reverse. Often referred to as the FFT method.
- Fill a length
$k$ circular buffer$C \in \mathbb{C}^{N \times M \times k}$ with collected CSI data, treating data corresponding to each transmitter as if it was a completely new measurement. - For each subcarrier
$n$ , let$C_n \in \mathbb{C}^{M\times k}$ be a matrix whose columns are CSI data for each receiver, and let$\mu_n \in \mathbb{C}^M$ be the average of each row of$C_n$ . Compute the covariance matrix$S_n = \frac{1}{k-1}(C_n - \mu_n)(C_n - \mu_n)^*$ (broadcasting the subtraction). - Compute the per-subcarrier profile
$p_{i,n} = \Re \{a(\theta_i)^*S_n a(\theta_i)\}$ . - Average across subcarriers to compute
$p_i = \frac{1}{n}\sum_n p_{i,n}$ .
This method only requires using one subcarrier, not necessarily all of them.
Uses the first principal component to merge CSI data from multiple frames. The SVD alleviates the noise present in methods that only use the current frame.
- Fill a length
$k$ circular buffer$C \in \mathbb{C}^{NM \times k}$ with collected CSI matrices that have been turned into vectors by stacking their columns, treating data corresponding to each transmitter as if it was a completely new measurement. - Compute the leading left singular vector
$u \in \mathbb{C}^{NM}$ of$C$ . - Unvectorize
$u$ into a CSI matrix$X \in \mathbb{C}^{N \times M}$ . - Compute the conventional beamforming profile
$p = |A^*X^*B|$ .
A method developed as part of the original WiROS source code, originally named rx_svd
. This method provides a significant speed boost over the full_svd method while providing results of comparable quality.
- Fill a length
$k$ circular buffer$C \in \mathbb{C}^{N \times M \times k}$ with collected CSI data, treating data corresponding to each transmitter as if it was a completely new measurement. - For each subcarrier
$n$ , compute the leading left singular vector$u_n \in \mathbb{C}^{M}$ of the$M \times k$ matrix corresponding to the data in$C$ for the$n$ 'th subcarrier. - Collect
$u_n$ into a CSI matrix$X \in \mathbb{C}^{N \times M}$ , where$[X]_{n,\cdot} = u_n$ . - Compute the conventional beamforming profile
$p = |A^*X^*B|$ .
The MUSIC algorithm is a subspace method. It assumes that the eigenspace of the covariance matrix can be partitioned into a subspace corresponding to the signal of interest and a subspace corresponding to noise. MUSIC identifies a basis for the noise subspace and rejects steering vectors that are close to it.
This version of the algorithm estimates the number of incoming wavefronts.
- Fill a length
$k$ circular buffer$C \in \mathbb{C}^{N \times M \times k}$ with collected CSI data, treating data corresponding to each transmitter as if it was a completely new measurement. - Stack subcarriers with buffer samples and reshape
$C \in \mathbb{C}^{M \times Nk}$ . Let$\mu \in \mathbb{C}^M$ be the average of each row of$C$ . Compute the covariance matrix$R = \frac{1}{Nk-1}(C - \mu)(C - \mu)^*$ (broadcasting the subtraction). - Let
$e_i$ and$v_i$ be the eigenvalues and eigenvectors of$R$ respectively. Create a basis for the noise subspace$\mathcal E = \{e_i \mid e_i < \alpha \cdot \max_j e_j\}$ , where$\alpha$ is a threshold parameter (normally$0.1$ ). - Let
$E \in \mathbb{C}^{M \times L}$ be a matrix whose columns are elements of$\mathcal E$ , so that the column space of$E$ is the noise subspace. - Compute the profile
$p_{i} = \frac{1}{\Re \left\{a(\theta_i)^* EE^* a(\theta_i)\right\}}$ .
Capon beamforming, also known as the Minimum Variance Distortionless Response (MVDR). This algorithm is an adaptive beamformer, and has better performance than conventional beamforming without the need to select or estimate the number of incoming wavefronts like in MUSIC.
- Fill a length
$k$ circular buffer$C \in \mathbb{C}^{N \times M \times k}$ with collected CSI data, treating data corresponding to each transmitter as if it was a completely new measurement. - Stack subcarriers with buffer samples and reshape
$C \in \mathbb{C}^{M \times Nk}$ . Let$\mu \in \mathbb{C}^M$ be the average of each row of$C$ . Compute the covariance matrix$R = \frac{1}{Nk-1}(C - \mu)(C - \mu)^*$ (broadcasting the subtraction). - Compute the profile
$p_{i} = \frac{1}{\Re \left\{a(\theta_i)^* R^{-1} a(\theta_i)\right\}}$ .