TI-radar AWR1843 C674x DSP core  1
dss_data_path.c File Reference

Implements Data path processing functionality. More...

#include <stdint.h>
#include <stdlib.h>
#include <stddef.h>
#include <string.h>
#include <stdio.h>
#include <math.h>
#include <xdc/std.h>
#include <xdc/cfg/global.h>
#include <xdc/runtime/IHeap.h>
#include <xdc/runtime/System.h>
#include <xdc/runtime/Error.h>
#include <xdc/runtime/Memory.h>
#include <ti/sysbios/BIOS.h>
#include <ti/sysbios/knl/Task.h>
#include <ti/sysbios/knl/Event.h>
#include <ti/sysbios/knl/Semaphore.h>
#include <ti/sysbios/knl/Clock.h>
#include <ti/sysbios/heaps/HeapBuf.h>
#include <ti/sysbios/heaps/HeapMem.h>
#include <ti/drivers/osal/DebugP.h>
#include <assert.h>
#include <ti/common/sys_common.h>
#include <ti/drivers/osal/SemaphoreP.h>
#include <ti/drivers/edma/edma.h>
#include <ti/drivers/esm/esm.h>
#include <ti/drivers/soc/soc.h>
#include <ti/utils/cycleprofiler/cycle_profiler.h>
#include <ti/alg/mmwavelib/mmwavelib.h>
#include "gen_twiddle_fft32x32.h"
#include "gen_twiddle_fft16x16.h"
#include "DSP_fft32x32.h"
#include "DSP_fft16x16.h"
#include <ti/mathlib/mathlib.h>
#include <common/app_cfg.h>
#include "dss_data_path.h"
#include "dss_config_edma_util.h"
#include "clusteringDBscan.h"
#include "EKF_XYZ_Interface.h"
#include "common/mmWave_XSS.h"
Include dependency graph for dss_data_path.c:

Go to the source code of this file.

Macros

#define DebugP_ASSERT_ENABLED   1
 
#define ROUND(x)   ((x) < 0 ? ((x) - 0.5) : ((x) + 0.5) )
 
#define SOC_XWR18XX_DSS_L3RAM_SIZE   0x100000
 
#define MMW_ADCBUF_SIZE   0x4000U
 
#define MMW_L2_HEAP_SIZE   0x19000U
 L2 heap used for allocating buffers in L2 SRAM, mostly scratch buffers. More...
 
#define MMW_L1_HEAP_SIZE   0x4000U
 L1 heap used for allocating buffers in L1D SRAM, mostly scratch buffers. More...
 
#define FFT_WINDOW_INT16   0
 
#define FFT_WINDOW_INT32   1
 
#define MMW_WIN_HAMMING   0
 
#define MMW_WIN_BLACKMAN   1
 
#define MMW_WIN_RECT   2
 
#define MMW_WIN_HANNING_RECT   3
 
#define ROUNDF(x)   ((x) < 0 ? ((x) - 0.5f) : ((x) + 0.5f) )
 
#define pingPongId(x)   ((x) & 0x1U)
 
#define isPong(x)   (pingPongId(x))
 
#define SOC_MAX_NUM_RX_ANTENNAS   4
 
#define SOC_MAX_NUM_TX_ANTENNAS   3
 
#define ALIGN(x, a)   (((x)+((a)-1))&~((a)-1))
 
#define MMW_ALLOC_BUF(name, nameType, startAddr, alignment, size)
 
#define TWENTY_TWO_DB_DOPPLER_SNR   ((22 *(256))/6)
 
#define EIGHTEEN_DB_DOPPLER_SNR   ((18 *(256))/6)
 
#define ZERO_POINT_FIVE_METERS   (0.5f * 128)
 
#define FOUR_POINT_ZERO_METERS   (4 * 128)
 

Functions

void MmwDemo_genWindow (void *win, uint32_t windowDatumType, uint32_t winLen, uint32_t winGenLen, int32_t oneQformat, uint32_t winType)
 
uint32_t findKLargestPeaks (uint16_t *restrict cfarDetObjIndexBuf, uint16_t *restrict cfarDetObjSNR, uint32_t numDetObjPerCfar, uint16_t *restrict sumAbs, uint16_t numBins, uint16_t K)
 
uint32_t pruneToPeaks (uint16_t *restrict cfarDetObjIndexBuf, uint16_t *restrict cfarDetObjSNR, uint32_t numDetObjPerCfar, uint16_t *restrict sumAbs, uint16_t numBins)
 
uint32_t pruneToPeaksOrNeighbourOfPeaks (uint16_t *restrict cfarDetObjIndexBuf, uint16_t *restrict cfarDetObjSNR, uint32_t numDetObjPerCfar, uint16_t *restrict sumAbs, uint16_t numBins)
 
uint32_t findandPopulateIntersectionOfDetectedObjects (DSS_DataPathObj *restrict obj, uint32_t numDetObjPerCfar, uint16_t dopplerLine, uint32_t numDetObj2D, uint16_t *restrict sumAbsRange)
 
uint32_t findandPopulateDetectedObjects (DSS_DataPathObj *restrict obj, uint32_t numDetObjPerCfar, uint16_t dopplerLine, uint32_t numDetObj2D, uint16_t *restrict sumAbsRange)
 
uint32_t MmwDemo_cfarPeakGrouping (MmwDemo_detectedObjActual *objOut, uint32_t numDetectedObjects, uint16_t *detMatrix, uint32_t numRangeBins, uint32_t numDopplerBins, uint32_t groupInDopplerDirection, uint32_t groupInRangeDirection)
 
uint32_t secondDimFFTandLog2Computation (DSS_DataPathObj *obj, uint16_t *sumAbs, uint16_t checkDetMatrixTx, uint16_t rangeIdx, uint32_t *pingPongIdxPtr)
 
uint32_t cfarCa_SO_dBwrap_withSNR (const uint16_t inp[restrict], uint16_t out[restrict], uint16_t outSNR[restrict], uint32_t len, uint32_t const1, uint32_t const2, uint32_t guardLen, uint32_t noiseLen)
 Function Name : cfarCa_SO_dBwrap_withSNR. More...
 
uint32_t cfarCadB_SO_withSNR (const uint16_t inp[restrict], uint16_t out[restrict], uint16_t outSNR[restrict], uint32_t len, uint32_t const1, uint32_t const2, uint32_t guardLen, uint32_t noiseLen, uint32_t minIndxToIgnoreHPF)
 Function Name : cfarCadB_SO_withSNR. More...
 
uint32_t aziEleProcessing (DSS_DataPathObj *obj, uint32_t subframeIndx)
 
uint16_t computeSinAzimSNR (float *azimuthMagSqr, uint16_t azimIdx, uint16_t numVirtualAntAzim, uint16_t numAngleBins, uint16_t xyzOutputQFormat)
 
float antilog2 (int32_t inputActual, uint16_t fracBitIn)
 
void associateClustering (clusteringDBscanOutput_t *restrict output, clusteringDBscanReport_t *restrict state, uint16_t maxNumTrackers, int32_t epsilon2, int32_t vFactor)
 
uint32_t cfarPeakGroupingAlongDoppler (MmwDemo_objRaw2D_t *restrict objOut, uint32_t numDetectedObjects, uint16_t *detMatrix, uint32_t numRangeBins, uint32_t numDopplerBins)
 
void populateOutputs (DSS_DataPathObj *obj)
 
uint32_t pruneTrackingInput (trackingInputReport_t *trackingInput, uint32_t numCluster)
 
float quadraticInterpFltPeakLoc (float *restrict y, int32_t len, int32_t indx)
 
float quadraticInterpLog2ShortPeakLoc (uint16_t *restrict y, int32_t len, int32_t indx, uint16_t fracBitIn)
 
void MmwDemo_XYcalc (DSS_DataPathObj *obj, uint32_t objIndex, uint16_t azimIdx, float *azimuthMagSqr)
 
void MmwDemo_addDopplerCompensation (int32_t dopplerIdx, int32_t numDopplerBins, uint32_t *azimuthModCoefs, uint32_t *azimuthModCoefsThirdBin, uint32_t *azimuthModCoefsTwoThirdBin, int64_t *azimuthIn, uint32_t numAnt, uint32_t numTxAnt, uint16_t txAntIdx)
 Function Name : MmwDemo_DopplerCompensation. More...
 
static void MmwDemo_rxChanPhaseBiasCompensation (uint32_t *rxChComp, int64_t *input, uint32_t numAnt)
 Function Name : MmwDemo_rxChanPhaseBiasCompensation. More...
 
uint8_t select_channel (uint8_t subframeIndx, uint8_t pingPongId, uint8_t option0ping, uint8_t option0pong)
 
void MmwDemo_startDmaTransfer (EDMA_Handle handle, uint8_t channelId0, uint8_t subframeIndx)
 
void MmwDemo_resetDopplerLines (MmwDemo_1D_DopplerLines_t *ths)
 
void MmwDemo_setDopplerLine (MmwDemo_1D_DopplerLines_t *ths, uint16_t dopplerIndex)
 
uint32_t MmwDemo_isSetDopplerLine (MmwDemo_1D_DopplerLines_t *ths, uint16_t index)
 
int32_t MmwDemo_getDopplerLine (MmwDemo_1D_DopplerLines_t *ths)
 
uint32_t MmwDemo_pow2roundup (uint32_t x)
 
void MmwDemo_XYestimation (DSS_DataPathObj *obj, uint32_t objIndex)
 
void MmwDemo_XYZestimation (DSS_DataPathObj *obj, uint32_t objIndex)
 
void MmwDemo_dataPathWait1DInputData (DSS_DataPathObj *obj, uint32_t pingPongId, uint32_t subframeIndx)
 
void MmwDemo_dataPathWait1DOutputData (DSS_DataPathObj *obj, uint32_t pingPongId, uint32_t subframeIndx)
 
void MmwDemo_dataPathWait2DInputData (DSS_DataPathObj *obj, uint32_t pingPongId, uint32_t subframeIndx)
 
void MmwDemo_dataPathWait3DInputData (DSS_DataPathObj *obj, uint32_t pingPongId, uint32_t subframeIndx)
 
void MmwDemo_dataPathWaitTransDetMatrix (DSS_DataPathObj *obj, uint8_t subframeIndx)
 
void MmwDemo_dataPathWaitTransDetMatrix2 (DSS_DataPathObj *obj, uint32_t subframeIndx)
 
int32_t MmwDemo_dataPathConfigEdma (DSS_DataPathObj *obj)
 
uint32_t rangeBasedPruning (MmwDemo_detectedObjActual *restrict objOut, MmwDemo_objRaw2D_t *restrict objRaw, RangeDependantThresh_t *restrict SNRThresh, RangeDependantThresh_t *restrict peakValThresh, uint32_t numDetectedObjects, uint32_t numDopplerBins, uint32_t maxRange, uint32_t minRange)
 
void MmwDemo_magnitudeSquared (cmplx32ReIm_t *restrict inpBuff, float *restrict magSqrdBuff, uint32_t numSamples)
 
void MmwDemo_dcRangeSignatureCompensation (DSS_DataPathObj *obj, uint8_t chirpPingPongId)
 
void MmwDemo_interChirpProcessing (DSS_DataPathObj *obj, uint32_t chirpPingPongId, uint8_t subframeIndx)
 
void MmwDemo_interFrameProcessing (DSS_DataPathObj *obj, uint8_t subframeIndx)
 
void MmwDemo_processChirp (DSS_DataPathObj *obj, uint8_t subframeIndx)
 
void MmwDemo_waitEndOfChirps (DSS_DataPathObj *obj, uint8_t subframeIndx)
 
void calc_cmplx_exp (cmplx16ImRe_t *dftSinCos, float i, uint32_t dftLen)
 
void MmwDemo_genDftSinCosTable (cmplx16ImRe_t *dftSinCosTable, cmplx16ImRe_t *dftHalfBinVal, cmplx16ImRe_t *dftThirdBinVal, cmplx16ImRe_t *dftTwoThirdBinVal, uint32_t dftLen)
 
void MmwDemo_edmaErrorCallbackFxn (EDMA_Handle handle, EDMA_errorInfo_t *errorInfo)
 
void MmwDemo_edmaTransferControllerErrorCallbackFxn (EDMA_Handle handle, EDMA_transferControllerErrorInfo_t *errorInfo)
 
void MmwDemo_dataPathInit1Dstate (DSS_DataPathObj *obj)
 
int32_t MmwDemo_dataPathInitEdma (DSS_DataPathObj *obj)
 
int32_t MmwDemo_dataPathCopyEdmaHandle (DSS_DataPathObj *objOutput, DSS_DataPathObj *objInput)
 
void MmwDemo_printHeapStats (char *name, uint32_t heapUsed, uint32_t heapSize)
 
void MmwDemo_dataPathConfigBuffers (DSS_DataPathObj *objIn, uint32_t adcBufAddress)
 
void MmwDemo_dataPathConfigFFTs (DSS_DataPathObj *obj)
 
uint32_t secondDimFFTandLog2Computation (DSS_DataPathObj *restrict obj, uint16_t *restrict sumAbs, uint16_t checkDetMatrixTx, uint16_t rangeIdx, uint32_t *pingPongIdxPtr)
 
uint32_t cfarPeakGroupingAlongDoppler (MmwDemo_objRaw2D_t *restrict objOut, uint32_t numDetectedObjects, uint16_t *restrict detMatrix, uint32_t numRangeBins, uint32_t numDopplerBins)
 
float convertSNRdBToVar (uint16_t SNRdB, uint16_t bitW, uint16_t n_samples, float resolution)
 
float convertSNRLinToVar (uint16_t SNRLin, uint16_t bitW, uint16_t n_samples, float resolution)
 
void MmwDemo_XYZcalc (DSS_DataPathObj *obj, uint32_t objIndex, uint16_t azimIdx, float *azimuthMagSqr)
 
void parkingAssistInit (DSS_DataPathObj *obj)
 

Variables

uint8_t gMmwL3 [SOC_XWR18XX_DSS_L3RAM_SIZE]
 
uint8_t gMmwL2 [MMW_L2_HEAP_SIZE]
 
uint8_t gMmwL1 [MMW_L1_HEAP_SIZE]
 
MCB gMCB
 Global Variable for tracking information required by the design. More...
 
volatile cycleLog_t gCycleLog
 

Detailed Description

Implements Data path processing functionality.

NOTE: (C) Copyright 2018 Texas Instruments, Inc.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

Neither the name of Texas Instruments Incorporated nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition in file dss_data_path.c.

Macro Definition Documentation

◆ ALIGN

#define ALIGN (   x,
 
)    (((x)+((a)-1))&~((a)-1))

◆ DebugP_ASSERT_ENABLED

#define DebugP_ASSERT_ENABLED   1

Definition at line 70 of file dss_data_path.c.

◆ EIGHTEEN_DB_DOPPLER_SNR

#define EIGHTEEN_DB_DOPPLER_SNR   ((18 *(256))/6)

Definition at line 4449 of file dss_data_path.c.

◆ FFT_WINDOW_INT16

#define FFT_WINDOW_INT16   0

Types of FFT window

FFT window 16 - samples format is int16_t

Definition at line 140 of file dss_data_path.c.

◆ FFT_WINDOW_INT32

#define FFT_WINDOW_INT32   1

FFT window 32 - samples format is int32_t

Definition at line 142 of file dss_data_path.c.

◆ FOUR_POINT_ZERO_METERS

#define FOUR_POINT_ZERO_METERS   (4 * 128)

Definition at line 4451 of file dss_data_path.c.

◆ isPong

#define isPong (   x)    (pingPongId(x))

Definition at line 159 of file dss_data_path.c.

◆ MMW_ADCBUF_SIZE

#define MMW_ADCBUF_SIZE   0x4000U

Definition at line 113 of file dss_data_path.c.

◆ MMW_ALLOC_BUF

#define MMW_ALLOC_BUF (   name,
  nameType,
  startAddr,
  alignment,
  size 
)
Value:
obj->name = (nameType *) ALIGN(startAddr, alignment); \
uint32_t name##_end = (uint32_t)obj->name + (size) * sizeof(nameType);

◆ MMW_L1_HEAP_SIZE

#define MMW_L1_HEAP_SIZE   0x4000U

L1 heap used for allocating buffers in L1D SRAM, mostly scratch buffers.

Definition at line 121 of file dss_data_path.c.

◆ MMW_L2_HEAP_SIZE

#define MMW_L2_HEAP_SIZE   0x19000U

L2 heap used for allocating buffers in L2 SRAM, mostly scratch buffers.

Definition at line 117 of file dss_data_path.c.

◆ MMW_WIN_BLACKMAN

#define MMW_WIN_BLACKMAN   1

Blackman window

Definition at line 148 of file dss_data_path.c.

◆ MMW_WIN_HAMMING

#define MMW_WIN_HAMMING   0

Hamming window

Definition at line 146 of file dss_data_path.c.

◆ MMW_WIN_HANNING_RECT

#define MMW_WIN_HANNING_RECT   3

rectangularized Hanning window

Definition at line 152 of file dss_data_path.c.

◆ MMW_WIN_RECT

#define MMW_WIN_RECT   2

Rectangular window

Definition at line 150 of file dss_data_path.c.

◆ pingPongId

#define pingPongId (   x)    ((x) & 0x1U)

Definition at line 158 of file dss_data_path.c.

◆ ROUND

#define ROUND (   x)    ((x) < 0 ? ((x) - 0.5) : ((x) + 0.5) )

Definition at line 109 of file dss_data_path.c.

◆ ROUNDF

#define ROUNDF (   x)    ((x) < 0 ? ((x) - 0.5f) : ((x) + 0.5f) )

simple rounding function for float

Definition at line 154 of file dss_data_path.c.

◆ SOC_MAX_NUM_RX_ANTENNAS

#define SOC_MAX_NUM_RX_ANTENNAS   4

Description
This function assigns memory locations to the different data buffers used in the MRR design.

Processing radar signals require a large number of scratch buffers for each step each of the processing stages (be it 1D-FFT, 2D-FFT, 3D-FFT, detection, angle estimation etc. However, since these stages occur serially, the memory assigned to a scratch buffer used in a previous stage can be re-used in the current stage. The Macro MMW_ALLOC_BUF in the following code allows specifying the start addresses such that the memory locations can be overlaid for efficient memory utilization.

In the MRR TI Design, there are two sub-frames per frame, and both sub-frames are processed separately. Therefore, nearly every scratch buffer memory location can be overlaid between the two. The allocation code is called twice to allocate memory for both sub-frames.

Certain memory locations are only necessary for a given processing path and are left unassigned for different programming paths.

Memory locations that correspond to the windowing functions, and twiddle factors, and estimated mean chirp need to be saved between sub-frames and as such cannot be overlaid.

Parameters
[in,out]objdata path object.
Return values
na.

Definition at line 2329 of file dss_data_path.c.

◆ SOC_MAX_NUM_TX_ANTENNAS

#define SOC_MAX_NUM_TX_ANTENNAS   3

Definition at line 2330 of file dss_data_path.c.

◆ SOC_XWR18XX_DSS_L3RAM_SIZE

#define SOC_XWR18XX_DSS_L3RAM_SIZE   0x100000

Definition at line 111 of file dss_data_path.c.

◆ TWENTY_TWO_DB_DOPPLER_SNR

#define TWENTY_TWO_DB_DOPPLER_SNR   ((22 *(256))/6)

Description
The function populates the object location arrays for transmission to MSS. The reason we do this additional step is to minimize the size of the the transmission because it shouldn't saturate the hold only the minimum information necessary for the external GUI are populated.

Parameters
[in]objdata path object.
Return values
none

Definition at line 4448 of file dss_data_path.c.

◆ ZERO_POINT_FIVE_METERS

#define ZERO_POINT_FIVE_METERS   (0.5f * 128)

Definition at line 4450 of file dss_data_path.c.

Function Documentation

◆ antilog2()

float antilog2 ( int32_t  inputActual,
uint16_t  fracBitIn 
)

Description
The function computes an antilog2 on the input which has a0 specified bitwidth.

Parameters
[in]input16 bit input with specified bitwidth.
[in]fracBitIninput fractional bitwidth.
Return values
2^(input/(2^fracBitIn))

Definition at line 4037 of file dss_data_path.c.

◆ associateClustering()

void associateClustering ( clusteringDBscanOutput_t *restrict  output,
clusteringDBscanReport_t *restrict  state,
uint16_t  maxNumClusters,
int32_t  epsilon2,
int32_t  vFactor 
)

Description
The function performs an association between the pre-existing clusters and the new clusters, with the intent that the cluster sizes are filtered.

Parameters
[in]outputThe output of the clustering algorithm.
[in]stateThe previous clustering output.
[in]maxNumTrackersThe maximum number of trackers.
[in]epsilon2distance metric param for association.
Return values
none

Definition at line 4322 of file dss_data_path.c.

◆ aziEleProcessing()

uint32_t aziEleProcessing ( DSS_DataPathObj obj,
uint32_t  subframeIndx 
)

Description
The function performs the third dimension processing, including the computation of the azimuth, and the x and y co-ordinate.

Parameters
[in]inputdata path object.
Return values
none

Azimuth calculation

Definition at line 4059 of file dss_data_path.c.

◆ calc_cmplx_exp()

void calc_cmplx_exp ( cmplx16ImRe_t *  dftSinCos,
float  i,
uint32_t  dftLen 
)

Definition at line 2090 of file dss_data_path.c.

◆ cfarCa_SO_dBwrap_withSNR()

uint32_t cfarCa_SO_dBwrap_withSNR ( const uint16_t  inp[restrict],
uint16_t  out[restrict],
uint16_t  outSNR[restrict],
uint32_t  len,
uint32_t  const1,
uint32_t  const2,
uint32_t  guardLen,
uint32_t  noiseLen 
)

Function Name : cfarCa_SO_dBwrap_withSNR.


Description : Performs a CFAR on an 16-bit unsigned input vector (CFAR-CA). The input values are assumed to be in logarithmic scale. So the comparison between the CUT and the noise samples is additive rather than multiplicative. Comparison is two-sided (wrap around when needed) for all CUTs.
Parameters
[in]inp: input array (16 bit unsigned numbers)
[in]out: output array (indices of detected peaks (zero based counting))
[in]outSNR: SNR array (SNR of detected peaks)
[in]len: number of elements in input array
[in]const1,const2: used to compare the Cell Under Test (CUT) to the sum of the noise cells: [noise sum /(2^(const2))] +const1 for two sided comparison.
[in]guardLen: one sided guard length
[in]noiseLen: one sided Noise length
[out]out: output array with indices of the detected peaks
Returns
Number of detected peaks (i.e length of out)
Precondition
Input (inp) and Output (out) arrays are non-aliased.

Definition at line 3546 of file dss_data_path.c.

◆ cfarCadB_SO_withSNR()

uint32_t cfarCadB_SO_withSNR ( const uint16_t  inp[restrict],
uint16_t  out[restrict],
uint16_t  outSNR[restrict],
uint32_t  len,
uint32_t  const1,
uint32_t  const2,
uint32_t  guardLen,
uint32_t  noiseLen,
uint32_t  minIndxToIgnoreHPF 
)

Function Name : cfarCadB_SO_withSNR.

Description
The MRR subframe achieves a maximum unambiguous velocity of 90kmph by using signal processing techniques that help disambiguate velocity. This method works by using two different estimates of velocity from the two kinds of chirps (‘fast chirps’ and ‘slow chirps’) transmitted in the MRR subframe. If the two velocity estimates do not agree, then velocity disambiguation is necessary. To disambiguate it is necessary to rationalize the two velocity measurements, and find out the disambiguation factor, k. If the naive maximum unambiguous velocity of the 'fast chirp' is v_f, and that of the 'slow chirp' is v_s. Then after the disambiguation process, the disambiguated velocity would 〖2kv〗_f+v, where v is the naïve estimated velocity from the ‘fast chirps’.

The disambiguation process works by using the 'fast chirp' velocity to compute different disambiguated velocity hypotheses. This is done by taking the 'fast chirp' velocity and adding 2k v_f, where k ∈ {-1,0,1} (an unwrapping process on the velocity estimate). These hypotheses are then converted to indices of the 'slow chirp' by finding the equivalent estimated velocities in the 'slow chirp' configuration ( essentially, undoing the unwrapping using v_s as the maximum unambiguous velocity).

If the index corresponding to one of the hypotheses has significant energy, then that hypothesis is considered to be valid. Disambiguation of up to 3x of the naive max-velocity is possible with this method, however, testing has only been done up to 90 kmph.

Parameters
[in,out]sumAbsThe slow chirps doppler bins at a certain range.
[in]fastChirpVelThe velocity estimate using the fast chirps (pre-disambiguation).
[in]fastChirpPeakValThe peak value of the index of the detected object from the fast chirp.
[in]objdata path object.
Return values
Ambiguityindex.

Description : Performs a CFAR SO on an 16-bit unsigned input vector. The input values are assumed to be in lograthimic scale. So the comparision between the CUT and the noise samples is additive rather than multiplicative.
Parameters
[in]inp: input array (16 bit unsigned numbers)
[in]out: output array (indices of detected peaks (zero based counting))
[in]outSNR: output array (SNR of detected peaks)
[in]len: number of elements in input array
[in]const1,const2: used to compare the Cell Under Test (CUT) to the sum of the noise cells: [noise sum /(2^(const2-1))]+const1 for one sided comparison (at the begining and end of the input vector). [noise sum /(2^(const2))]+const1 for two sided comparison
[in]guardLen: one sided guard length
[in]noiseLen: one sided noise length
[in]minIndxToIgnoreHPF: the number of indices to force one sided CFAR, so as to avoid false detections due to effect of the HPF.
[out]out: output array with indices of the detected peaks
Returns
Number of detected peaks (i.e length of out)
Precondition
Input (inp) and Output (out) arrays are non-aliased.

Definition at line 3400 of file dss_data_path.c.

◆ cfarPeakGroupingAlongDoppler() [1/2]

uint32_t cfarPeakGroupingAlongDoppler ( MmwDemo_objRaw2D_t *restrict  objOut,
uint32_t  numDetectedObjects,
uint16_t *  detMatrix,
uint32_t  numRangeBins,
uint32_t  numDopplerBins 
)

◆ cfarPeakGroupingAlongDoppler() [2/2]

uint32_t cfarPeakGroupingAlongDoppler ( MmwDemo_objRaw2D_t *restrict  objOut,
uint32_t  numDetectedObjects,
uint16_t *restrict  detMatrix,
uint32_t  numRangeBins,
uint32_t  numDopplerBins 
)

Description
The function groups neighboring peaks (only in the doppler direction) into one. For each
detected peak the function checks if the peak is greater than its neighbors. If this is true, the peak is copied to the output list of detected objects. The neighboring peaks that are used for checking are taken from the detection matrix and copied into 1x3 kernel regardless of whether they are CFAR detected or not.

Note: Function always reads 3 samples per detected object from L3 memory into local array.

Parameters
[out]objOutOutput array of detected objects after peak grouping
[in]objRawArray of detected objects after CFAR detection
[in]numDetectedObjectsNumber of detected objects by CFAR
[in]detMatrixDetection Range/Doppler matrix
[in]numDopplerBinsNumber of Doppler bins3401
Return values
Numberof detected objects after grouping

Definition at line 3845 of file dss_data_path.c.

◆ computeSinAzimSNR()

uint16_t computeSinAzimSNR ( float *  azimuthMagSqr,
uint16_t  azimIdx,
uint16_t  numVirtualAntAzim,
uint16_t  numAngleBins,
uint16_t  xyzOutputQFormat 
)

Description
The function

Parameters
[out]azimuthMagSqrInput array of the sum of the squares of the zero padded FFT output.
[in]azimIdxThe location of the peak of the detected object.
[in]numVirtualAntAzimthe size of the FFT input.
[in]numAngleBinsThe size of the FFT output.
[in]xyzOutputQFormatnumber of fractional bits in the output.
Return values
SNRlinearwith the programmed fractional bitwidth

Definition at line 3919 of file dss_data_path.c.

◆ convertSNRdBToVar()

float convertSNRdBToVar ( uint16_t  SNRdB,
uint16_t  bitW,
uint16_t  n_samples,
float  resolution 
)

Description
The function computes the CRLB of the given estimate given an SNR input (dB) and the number of samples used in the estimate, and the resolution of the estimate.

Parameters
[in]SNRdB16 bit input with specified bitwidth.
[in]bitWinput fractional bitwidth (for SNR in dB).
[in]n_samplesnumber of samples per chirp.
[in]resolutionrange resolution in meters.
Return values
CRLBin the specified resolution (with some lower bounds).

Definition at line 3971 of file dss_data_path.c.

◆ convertSNRLinToVar()

float convertSNRLinToVar ( uint16_t  SNRLin,
uint16_t  bitW,
uint16_t  n_samples,
float  resolution 
)

Description
The function computes the CRLB of the given estimate given an SNR input (linear) and the number of samples used in the estimate, and the resolution of the estimate.

The CRLB is lower bounded by the resolution.

Parameters
[in]SNRdB16 bit input with specified bitwidth.
[in]bitWinput fractional bitwidth.
[in]n_samplesnumber of samples per chirp.
[in]resolutionresolution in meters.
Return values
2^(input/(2^fracBitIn))

Definition at line 4008 of file dss_data_path.c.

◆ findandPopulateDetectedObjects()

uint32_t findandPopulateDetectedObjects ( DSS_DataPathObj *restrict  obj,
uint32_t  numDetObjPerCfar,
uint16_t  dopplerLine,
uint32_t  numDetObj2D,
uint16_t *restrict  sumAbsRange 
)

Description
This function populates the 2D cfar object

Parameters
[in,out]objdata path object.
[in]numDetObjPerCfarnumber of detected objects from the CFAR function.
[in]dopplerLineThe index of the doppler gate being processed.
[in]numDetObj2DThe total number of detected objects.
[in]sumAbsRangeThe sumAbs Array for the range dimension. It is used to populate the 'peakVal' on a per object basis.
Return values
Thetotal number of detected objects (including the results of the current intersection).

Definition at line 3130 of file dss_data_path.c.

◆ findandPopulateIntersectionOfDetectedObjects()

uint32_t findandPopulateIntersectionOfDetectedObjects ( DSS_DataPathObj *restrict  obj,
uint32_t  numDetObjPerCfar,
uint16_t  dopplerLine,
uint32_t  numDetObj2D,
uint16_t *restrict  sumAbsRange 
)

Description
This function finds the intersection of the 1D cfar objects (computed previously) and the outputs of the 2D CFAR function. The purpose is to select only those objects which have been detected in both the 1D and 2D CFARs.

Parameters
[in,out]objdata path object.
[in]numDetObjPerCfarnumber of detected objects from the CFAR function.
[in]dopplerLineThe index of the doppler gate being processed.
[in]numDetObj2DThe total number of detected objects.
[in]sumAbsRangeThe sumAbs Array for the range dimension. It is used to populate the 'peakVal' on a per object basis.
Return values
Thetotal number of detected objects (including the results of the current intersection).

Definition at line 3031 of file dss_data_path.c.

◆ findKLargestPeaks()

uint32_t findKLargestPeaks ( uint16_t *restrict  cfarDetObjIndexBuf,
uint16_t *restrict  cfarDetObjSNR,
uint32_t  numDetObjPerCfar,
uint16_t *restrict  sumAbs,
uint16_t  numBins,
uint16_t  K 
)

Description
This function finds the K strongest objects in a given list of objects. The 'strength' of an object is its 'peak value' corresponding to its index in the sumAbs Array.

Parameters
[in,out]cfarDetObjIndexBufThe indices of the detected objects.
[in,out]cfarDetObjSNRThe SNR of the detected objects.
[in]numDetObjPerCfarThe number of detected objects.
[in]sumAbsThe sumAbs array on which the CFAR was run.
[in]numBinsThe length of the cfarDetObjSNR and cfarDetObjIndexBuf array.
[in]KThe maximum number of objects to be returned by this function.
Return values
min(K,numDetObjPerCfar).

Definition at line 3276 of file dss_data_path.c.

◆ MmwDemo_addDopplerCompensation()

void MmwDemo_addDopplerCompensation ( int32_t  dopplerIdx,
int32_t  numDopplerBins,
uint32_t *  azimuthModCoefs,
uint32_t *  azimuthModCoefsThirdBin,
uint32_t *  azimuthModCoefsTwoThirdBin,
int64_t *  azimuthIn,
uint32_t  numAnt,
uint32_t  numTxAnt,
uint16_t  txAntIdx 
)

Function Name : MmwDemo_DopplerCompensation.


Description : Compensation of Doppler phase shift in the virtual antennas, (corresponding to second Tx antenna chirps). Symbols corresponding to virtual antennas, are rotated by half of the Doppler phase shift measured by Doppler FFT. The phase shift read from the table using half of the object Doppler index value. If the Doppler index is odd, an extra half of the bin phase shift is added.
Parameters
[in]dopplerIdx: Doppler index of the object
[in]numDopplerBins: Number of Doppler bins
[in]azimuthModCoefsTable with cos/sin values SIN in even position, COS in odd position exp(1j*2*pi*k/N) for k=0,...,N-1 where N is number of Doppler bins.
[out]azimuthModCoefsHalfBin: exp(1j*2*pi* 0.5 /N) //TODO change to 1/3 instead of 1/2 for the correction.
[in,out]azimuthIn:Pointer to antenna symbols to be Doppler compensated
[in]numAnt: Number of antenna symbols to be Doppler compensated
Returns
void

Definition at line 4866 of file dss_data_path.c.

◆ MmwDemo_cfarPeakGrouping()

uint32_t MmwDemo_cfarPeakGrouping ( MmwDemo_detectedObjActual objOut,
uint32_t  numDetectedObjects,
uint16_t *  detMatrix,
uint32_t  numRangeBins,
uint32_t  numDopplerBins,
uint32_t  groupInDopplerDirection,
uint32_t  groupInRangeDirection 
)

Description
The function groups neighboring peaks into one. The grouping is done according to two input flags: groupInDopplerDirection and groupInDopplerDirection. For each detected peak the function checks if the peak is greater than its neighbors. If this is true, the peak is copied to the output list of detected objects. The neighboring peaks that are used for checking are taken from the detection matrix and copied into 3x3 kernel regardless of whether they are CFAR detected or not. Note: Function always reads 9 samples per detected object from L3 memory into local array tempBuff, but it only needs to read according to input flags. For example if only the groupInDopplerDirection flag is set, it only needs to read middle row of the kernel, i.e. 3 samples per target from detection matrix.

Parameters
[out]objOutOutput array of detected objects after peak grouping
[in]objRawArray of detected objects after CFAR detection
[in]numDetectedObjectsNumber of detected objects by CFAR
[in]detMatrixDetection Range/Doppler matrix
[in]numDopplerBinsNumber of Doppler bins
[in]groupInDopplerDirectionFlag enables grouping in Doppler directiuon
[in]groupInRangeDirectionFlag enables grouping in Range directiuon
Return values
Numberof detected objects after grouping

Definition at line 3710 of file dss_data_path.c.

◆ MmwDemo_dataPathConfigBuffers()

void MmwDemo_dataPathConfigBuffers ( DSS_DataPathObj obj,
uint32_t  adcBufAddress 
)

Description
Creates heap in L2 and L3 and allocates data path buffers, The heap is destroyed at the end of the function.

Return values
NotApplicable.

Definition at line 2331 of file dss_data_path.c.

◆ MmwDemo_dataPathConfigEdma()

int32_t MmwDemo_dataPathConfigEdma ( DSS_DataPathObj obj)

Description
Configures all EDMA channels and param sets used in data path processing

This function is very similar to the dataPathConfigEDMA from the OOB demo, but with the difference that we have two subframes, and one subframe can support the maximum velocity enhancement modification. In this method , the 2nd dimension has two kinds of chirps and each chirp is repeated 'numDopplerBins' times, and each chirp has the same number of adc samples.

We would also like to ensure that when the data is transferred to L3 RAM, a range gate (i.e. doppler bins corresponding to a range bin) of each 'chirptype' is contiguous, so that a single EDMA can pull them both out in the 2nd dimension processing.

Hence the EDMAs corresponding to the transfer of 1D data to L3 and the transfer of data from L3 to L2 are modified.

Parameters
[in]objPointer to data path object array.
Return values
-1if error, 0 for no error

Definition at line 936 of file dss_data_path.c.

References DSS_DataPathObj_t::ADCdataBuf, DSS_DataPathObj_t::adcDataIn, BYTES_PER_SAMP_1D, BYTES_PER_SAMP_DET, EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, EDMAutil_configType1(), EDMAutil_configType2a(), EDMAutil_configType3(), MAX, MAX_VEL_ENH_PROCESSING, MRR_SF0_EDMA_CH_1D_IN_PING, MRR_SF0_EDMA_CH_1D_IN_PONG, MRR_SF0_EDMA_CH_1D_OUT_PING, MRR_SF0_EDMA_CH_1D_OUT_PONG, MRR_SF0_EDMA_CH_2D_IN_PING, MRR_SF0_EDMA_CH_2D_IN_PONG, MRR_SF0_EDMA_CH_3D_IN_PING, MRR_SF0_EDMA_CH_3D_IN_PONG, MRR_SF0_EDMA_CH_DET_MATRIX, MRR_SF0_EDMA_CH_DET_MATRIX2, NUM_SUBFRAMES, DSS_DataPathObj_t::numAdcSamples, DSS_DataPathObj_t::numRxAntennas, and DSS_DataPathObj_t::processingPath.

Here is the call graph for this function:

◆ MmwDemo_dataPathConfigFFTs()

void MmwDemo_dataPathConfigFFTs ( DSS_DataPathObj obj)

Description
Function to populate the twiddle factors for FFTS needed for the data path object.

Parameters
[in,out]objdata path object.
Return values
waitingTime.

Definition at line 2746 of file dss_data_path.c.

◆ MmwDemo_dataPathCopyEdmaHandle()

int32_t MmwDemo_dataPathCopyEdmaHandle ( DSS_DataPathObj objOutput,
DSS_DataPathObj objInput 
)

Description
This function copies the EDMA handles to all of the remaining data path objects.

Parameters
[in,out]objdata path object.
Return values
success.

Definition at line 2272 of file dss_data_path.c.

◆ MmwDemo_dataPathInit1Dstate()

void MmwDemo_dataPathInit1Dstate ( DSS_DataPathObj obj)

Description
This function initializes some of the states (counters) used for 1D processing.

Parameters
[in,out]objdata path object.
Return values
success/failure.

Definition at line 2198 of file dss_data_path.c.

◆ MmwDemo_dataPathInitEdma()

int32_t MmwDemo_dataPathInitEdma ( DSS_DataPathObj obj)

Description
This function copies the EDMA handles to all of the remaining data path objects.

Parameters
[in,out]objdata path object.
Return values
success/failure.

Definition at line 2223 of file dss_data_path.c.

◆ MmwDemo_dataPathWait1DInputData()

void MmwDemo_dataPathWait1DInputData ( DSS_DataPathObj obj,
uint32_t  pingPongId,
uint32_t  subframeIndx 
)

Description
Waits for 1D FFT data to be transferrd to input buffer. This is a blocking function.

Parameters
[in]objPointer to data path object
[in]pingPongIdping-pong id (ping is 0 and pong is 1)
[in]subframeIndx
Return values
NONE

Definition at line 703 of file dss_data_path.c.

References EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, MmwDemo_dssAssert, MRR_SF0_EDMA_CH_1D_IN_PING, MRR_SF0_EDMA_CH_1D_IN_PONG, and pingPongId.

◆ MmwDemo_dataPathWait1DOutputData()

void MmwDemo_dataPathWait1DOutputData ( DSS_DataPathObj obj,
uint32_t  pingPongId,
uint32_t  subframeIndx 
)

Description
Waits for 1D FFT data to be transferred to output buffer. This is a blocking function.

Parameters
[in]objPointer to data path object
[in]pingPongIdping-pong id (ping is 0 and pong is 1)
[in]subframeIndx
Return values
NONE

Definition at line 755 of file dss_data_path.c.

References EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, MmwDemo_dssAssert, MRR_SF0_EDMA_CH_1D_OUT_PING, MRR_SF0_EDMA_CH_1D_OUT_PONG, pingPongId, and select_channel().

Referenced by MmwDemo_processChirp().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MmwDemo_dataPathWait2DInputData()

void MmwDemo_dataPathWait2DInputData ( DSS_DataPathObj obj,
uint32_t  pingPongId,
uint32_t  subframeIndx 
)

Description
Waits for 1D FFT data to be transferred to input buffer for 2D-FFT caclulation. This is a blocking function.

Parameters
[in]objPointer to data path object
[in]pingPongIdping-pong id (ping is 0 and pong is 1)
[in]subframeIndex
Return values
NONE

Definition at line 786 of file dss_data_path.c.

References EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, MmwDemo_dssAssert, MRR_SF0_EDMA_CH_2D_IN_PING, MRR_SF0_EDMA_CH_2D_IN_PONG, pingPongId, and select_channel().

Here is the call graph for this function:

◆ MmwDemo_dataPathWait3DInputData()

void MmwDemo_dataPathWait3DInputData ( DSS_DataPathObj obj,
uint32_t  pingPongId,
uint32_t  subframeIndx 
)

Description
Waits for 1D FFT data to be transferred to input buffer for 3D-FFT calculation. This is a blocking function.

Parameters
[in]objPointer to data path object
[in]pingPongIdping-pong id (ping is 0 and pong is 1)
[in]subframeIndx
Return values
NONE

Definition at line 818 of file dss_data_path.c.

References EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, MmwDemo_dssAssert, MRR_SF0_EDMA_CH_3D_IN_PING, MRR_SF0_EDMA_CH_3D_IN_PONG, pingPongId, and select_channel().

Here is the call graph for this function:

◆ MmwDemo_dataPathWaitTransDetMatrix()

void MmwDemo_dataPathWaitTransDetMatrix ( DSS_DataPathObj obj,
uint8_t  subframeIndx 
)

Description
Waits for 2D FFT calculated data to be transferred out from L2 memory to detection matrix located in L3 memory. This is a blocking function.

Parameters
[in]objPointer to data path object
[in]subframeIndx
Return values
NONE

Definition at line 848 of file dss_data_path.c.

References EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, MmwDemo_dssAssert, and MRR_SF0_EDMA_CH_DET_MATRIX.

◆ MmwDemo_dataPathWaitTransDetMatrix2()

void MmwDemo_dataPathWaitTransDetMatrix2 ( DSS_DataPathObj obj,
uint32_t  subframeIndx 
)

Description
Waits for 2D FFT data to be transferred from detection matrix in L3 memory to L2 memory for CFAR detection in range direction. This is a blocking function.

Parameters
[in]objPointer to data path object
[in]subframeIndx
Return values
NONE

Definition at line 885 of file dss_data_path.c.

References EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, MmwDemo_dssAssert, and MRR_SF0_EDMA_CH_DET_MATRIX2.

◆ MmwDemo_dcRangeSignatureCompensation()

void MmwDemo_dcRangeSignatureCompensation ( DSS_DataPathObj obj,
uint8_t  chirpPingPongId 
)

Description
Compensation of DC range antenna signature (unused currently)

Return values
NotApplicable.

Definition at line 1447 of file dss_data_path.c.

◆ MmwDemo_edmaErrorCallbackFxn()

void MmwDemo_edmaErrorCallbackFxn ( EDMA_Handle  handle,
EDMA_errorInfo_t *  errorInfo 
)

Description
This is a callback function for EDMA errors.

Parameters
[in]handleEDMA Handle.
[in]errorInfoEDMA error info.
Return values
n/a.

Definition at line 2163 of file dss_data_path.c.

◆ MmwDemo_edmaTransferControllerErrorCallbackFxn()

void MmwDemo_edmaTransferControllerErrorCallbackFxn ( EDMA_Handle  handle,
EDMA_transferControllerErrorInfo_t *  errorInfo 
)

Description
This is a callback function for EDMA TC errors.

Parameters
[in]handleEDMA Handle.
[in]errorInfoEDMA TC error info.
Return values
n/a.

Definition at line 2178 of file dss_data_path.c.

◆ MmwDemo_genDftSinCosTable()

void MmwDemo_genDftSinCosTable ( cmplx16ImRe_t *  dftSinCosTable,
cmplx16ImRe_t *  dftHalfBinVal,
cmplx16ImRe_t *  dftThirdBinVal,
cmplx16ImRe_t *  dftTwoThirdBinVal,
uint32_t  dftLen 
)

Description
Generate SIN/COS table in Q15 (SIN to even int16 location, COS to odd int16 location. Also generates Sin/Cos at half the bin value The table is generated as T[i]=cos[2*pi*i/N] - 1j*sin[2*pi*i/N] for i=0,...,N where N is dftLen The half bn value is calculated as: TH = cos[2*pi*0.5/N] - 1j*sin[2*pi*0.5/N]

Parameters
[out]dftSinCosTableArray with generated Sin Cos table
[out]dftHalfBinValSin/Cos value at half the bin
[in]dftLenLength of the DFT
Return values
NotApplicable.

Definition at line 2130 of file dss_data_path.c.

◆ MmwDemo_genWindow()

void MmwDemo_genWindow ( void *  win,
uint32_t  windowDatumType,
uint32_t  winLen,
uint32_t  winGenLen,
int32_t  oneQformat,
uint32_t  winType 
)

Description
Function to generate a single FFT window sample.

Parameters
[out]winPointer to calculated window samples.
[in]windowDatumTypeWindow samples data format. For windowDatumType = FFT_WINDOW_INT16, the samples format is int16_t. For windowDatumType = FFT_WINDOW_INT32, the samples format is int32_t.
[in]winLenNominal window length
[in]winGenLenNumber of generated samples
[in]oneQformatQ format of samples, oneQformat is the value of one in the desired format.
[in]winTypeType of window, one of MMW_WIN_BLACKMAN, MMW_WIN_HANNING, or MMW_WIN_RECT.
Return values
none.

Definition at line 2796 of file dss_data_path.c.

◆ MmwDemo_getDopplerLine()

int32_t MmwDemo_getDopplerLine ( MmwDemo_1D_DopplerLines_t ths)

Description
Gets the Doppler index from the Doppler line bit mask, starting from the smallest active Doppler lin (bin). Subsequent calls return the next active Doppler line.

See also
MmwDemo_resetDopplerLines

Definition at line 377 of file dss_data_path.c.

References MmwDemo_1D_DopplerLines::currentIndex, and MmwDemo_1D_DopplerLines::dopplerLineMask.

◆ MmwDemo_interChirpProcessing()

void MmwDemo_interChirpProcessing ( DSS_DataPathObj obj,
uint32_t  chirpPingPongId,
uint8_t  subframeIndx 
)

Description
Interchirp processing. It is executed per chirp event, after ADC buffer is filled with chirp samples.

Return values
NotApplicable.

Definition at line 1562 of file dss_data_path.c.

Referenced by MmwDemo_processChirp().

Here is the caller graph for this function:

◆ MmwDemo_interFrameProcessing()

void MmwDemo_interFrameProcessing ( DSS_DataPathObj obj,
uint8_t  subframeIndx 
)

Description
Interframe processing. It is called from MmwDemo_dssDataPathProcessEvents after all chirps of the frame have been received and 1D FFT processing on them has been completed.

Return values
NotApplicable.

Definition at line 1633 of file dss_data_path.c.

◆ MmwDemo_isSetDopplerLine()

uint32_t MmwDemo_isSetDopplerLine ( MmwDemo_1D_DopplerLines_t ths,
uint16_t  index 
)

Description
Checks whether Doppler line is active in the observed frame. It checks whether the bit is set in the Doppler line bit mask corresponding to Doppler line on which CFAR in Doppler direction detected object.

See also
MmwDemo_resetDopplerLines

Definition at line 352 of file dss_data_path.c.

References MmwDemo_1D_DopplerLines::dopplerLineMask.

◆ MmwDemo_magnitudeSquared()

void MmwDemo_magnitudeSquared ( cmplx32ReIm_t *restrict  inpBuff,
float *restrict  magSqrdBuff,
uint32_t  numSamples 
)

Description
Outputs magnitude squared float array of input complex32 array

Return values
NotApplicable.

Definition at line 1428 of file dss_data_path.c.

◆ MmwDemo_pow2roundup()

uint32_t MmwDemo_pow2roundup ( uint32_t  x)

Description
Power of 2 round up function.

Definition at line 404 of file dss_data_path.c.

◆ MmwDemo_printHeapStats()

void MmwDemo_printHeapStats ( char *  name,
uint32_t  heapUsed,
uint32_t  heapSize 
)

Description
This function holds the last remaining 'printf' in the entire MRR, and prints the space remaining in the global heap.

Parameters
[in,out]objdata path object.
Return values
na.

Definition at line 2297 of file dss_data_path.c.

◆ MmwDemo_processChirp()

void MmwDemo_processChirp ( DSS_DataPathObj obj,
uint8_t  subframeIndx 
)

Description
Chirp processing. It is called from MmwDemo_dssDataPathProcessEvents. It is executed per chirp.

The range FFT output is transferred in a transpose manner to L3 using an EDMA. This is done so that the 2nd FFT data can be pulled out using a non-transpose EDMA (which is more efficient)

The EDMA transfer requires a destination offset (radarCubeOffset) that is proportional with the chirp number.

For the MAX_VEL_ENH chirp, there are two chirp types (fast and slow), they are stored consecutively ( for e.g. chirp 1 of the fast chirp is directly followed by chirp 1 of the slow chirp.

Return values
NotApplicable.
  1. Book keeping.
  2. Range processing.

Definition at line 1974 of file dss_data_path.c.

References DSS_DataPathObj_t::chirpCount, DSS_DataPathObj_t::chirpTypeCount, DSS_DataPathObj_t::dopplerBinCount, EDMA_INSTANCE_DSS, DSS_DataPathObj_t::edmaHandle, EDMAutil_triggerType3(), gCycleLog, cycleLog_t_::interChirpWaitTime, isPong, MAX_VEL_ENH_PROCESSING, MmwDemo_dataPathWait1DOutputData(), MmwDemo_interChirpProcessing(), MRR_EDMA_TRIGGER_ENABLE, MRR_SF0_EDMA_CH_1D_OUT_PING, MRR_SF0_EDMA_CH_1D_OUT_PONG, DSS_DataPathObj_t::numDopplerBins, DSS_DataPathObj_t::numRxAntennas, DSS_DataPathObj_t::numTxAntennas, pingPongId, DSS_DataPathObj_t::processingPath, DSS_DataPathObj_t::radarCube, and DSS_DataPathObj_t::txAntennaCount.

Here is the call graph for this function:

◆ MmwDemo_resetDopplerLines()

void MmwDemo_resetDopplerLines ( MmwDemo_1D_DopplerLines_t ths)

Description
Resets the Doppler line bit mask. Doppler line bit mask indicates Doppler lines (bins) on wich the CFAR in Doppler direction detected objects. After the CFAR in Doppler direction is completed for all range bins, the CFAR in range direction is performed on indicated Doppler lines. The array dopplerLineMask is uint32_t array. The LSB bit of the first word corresponds to Doppler line (bin) zero.

Definition at line 323 of file dss_data_path.c.

References MmwDemo_1D_DopplerLines::currentIndex, MmwDemo_1D_DopplerLines::dopplerLineMask, and MmwDemo_1D_DopplerLines::dopplerLineMaskLen.

◆ MmwDemo_rxChanPhaseBiasCompensation()

static void MmwDemo_rxChanPhaseBiasCompensation ( uint32_t *  rxChComp,
int64_t *  input,
uint32_t  numAnt 
)
inlinestatic

Function Name : MmwDemo_rxChanPhaseBiasCompensation.


Description : Compensation of rx channel phase bias
Parameters
[in]rxChComp: rx channel compensation coefficient
[in]input: 32-bit complex input symbols must be 64 bit aligned
[in]numAnt: number of symbols
Returns
void

Definition at line 4939 of file dss_data_path.c.

◆ MmwDemo_setDopplerLine()

void MmwDemo_setDopplerLine ( MmwDemo_1D_DopplerLines_t ths,
uint16_t  dopplerIndex 
)

Description
Sets the bit in the Doppler line bit mask dopplerLineMask corresponding to Doppler line on which CFAR in Doppler direction detected object. Indicating the Doppler line being active in observed frame.

See also
MmwDemo_resetDopplerLines

Definition at line 336 of file dss_data_path.c.

References MmwDemo_1D_DopplerLines::dopplerLineMask.

◆ MmwDemo_startDmaTransfer()

void MmwDemo_startDmaTransfer ( EDMA_Handle  handle,
uint8_t  channelId0,
uint8_t  subframeIndx 
)

Description
Starts a DMA transfer on a specifed channel corresponding to a given subframe.

Definition at line 303 of file dss_data_path.c.

◆ MmwDemo_waitEndOfChirps()

void MmwDemo_waitEndOfChirps ( DSS_DataPathObj obj,
uint8_t  subframeIndx 
)

Description
Wait for transfer of data corresponding to the last 2 chirps (ping/pong) to the radarCube matrix before starting interframe processing.

Return values
NotApplicable.

Definition at line 2079 of file dss_data_path.c.

◆ MmwDemo_XYcalc()

void MmwDemo_XYcalc ( DSS_DataPathObj obj,
uint32_t  objIndex,
uint16_t  azimIdx,
float *  azimuthMagSqr 
)

Description
Calculates X/Y coordinates in meters based on the maximum position in the magnitude square of the azimuth FFT output. The function is called per detected object.

Parameters
[in]objPointer to data path object
[in]objIndexDetected object index
[in]azimIdxIndex of the peak position in Azimuth FFT output
[in]azimuthMagSqrazimuth energy array
Return values
NONE

Definition at line 4982 of file dss_data_path.c.

Referenced by MmwDemo_XYestimation().

Here is the caller graph for this function:

◆ MmwDemo_XYestimation()

void MmwDemo_XYestimation ( DSS_DataPathObj obj,
uint32_t  objIndex 
)

Description
Calculates X/Y coordinates in meters based on the maximum position in the magnitude square of the azimuth FFT output. The function is called per detected object. The detected object structure already has populated range and doppler indices. This function finds maximum index in the azimuth FFT, calculates X and Y and coordinates and stores them into object fields along with the peak height. Also it populates the azimuth index in azimuthMagSqr array.

Parameters
[in]objPointer to data path object
[in]objIndexDetected object index
Return values
NONE

Definition at line 431 of file dss_data_path.c.

References DSS_DataPathObj_t::azimuthMagSqr, DSS_DataPathObj_t::detObj2D, MmwDemo_MultiObjBeamFormingCfg_t::enabled, DSS_DataPathObj_t::maxUnambiguousVel, MmwDemo_XYcalc(), MRR_MAX_OBJ_OUT, DSS_DataPathObj_t::multiObjBeamFormingCfg, MmwDemo_MultiObjBeamFormingCfg_t::multiPeakThrsScal, DSS_DataPathObj_t::numAngleBins, DSS_DataPathObj_t::numDetObj, POINT_CLOUD_PROCESSING, DSS_DataPathObj_t::processingPath, MmwDemo_detectedObjActual_t::speed, and DSS_DataPathObj_t::xyzOutputQFormat.

Here is the call graph for this function:

◆ MmwDemo_XYZcalc()

void MmwDemo_XYZcalc ( DSS_DataPathObj obj,
uint32_t  objIndex,
uint16_t  azimIdx,
float *  azimuthMagSqr 
)

Description
Calculates X/Y coordinates in meters based on the maximum position in the magnitude square of the azimuth FFT output. The function is called per detected object.

Parameters
[in]objPointer to data path object
[in]objIndexDetected object index
[in]azimIdxIndex of the peak position in Azimuth FFT output
[in]azimuthMagSqrazimuth energy array
Return values
NONE

Definition at line 5052 of file dss_data_path.c.

Referenced by MmwDemo_XYZestimation().

Here is the caller graph for this function:

◆ MmwDemo_XYZestimation()

void MmwDemo_XYZestimation ( DSS_DataPathObj obj,
uint32_t  objIndex 
)

Description
Calculates X/Y coordinates in meters based on the maximum position in the magnitude square of the azimuth FFT output. The function is called per detected object. The detected object structure already has populated range and doppler indices. This function finds maximum index in the azimuth FFT, calculates X and Y and coordinates and stores them into object fields along with the peak height. Also it populates the azimuth index in azimuthMagSqr array.

Parameters
[in]objPointer to data path object
[in]objIndexDetected object index
Return values
NONE

Definition at line 563 of file dss_data_path.c.

References DSS_DataPathObj_t::azimuthMagSqr, DSS_DataPathObj_t::detObj2D, MmwDemo_MultiObjBeamFormingCfg_t::enabled, MAX_VEL_POINT_CLOUD_PROCESSING_IS_ENABLED, DSS_DataPathObj_t::maxUnambiguousVel, MmwDemo_XYZcalc(), MRR_MAX_OBJ_OUT, DSS_DataPathObj_t::multiObjBeamFormingCfg, MmwDemo_MultiObjBeamFormingCfg_t::multiPeakThrsScal, DSS_DataPathObj_t::numAngleBins, DSS_DataPathObj_t::numDetObj, POINT_CLOUD_PROCESSING, DSS_DataPathObj_t::processingPath, MmwDemo_detectedObjActual_t::speed, and DSS_DataPathObj_t::xyzOutputQFormat.

Here is the call graph for this function:

◆ parkingAssistInit()

void parkingAssistInit ( DSS_DataPathObj obj)

Description
Initialize the 'parking assist bins' state which is essentially the closest obstruction upper bounded by its maximum value.

Parameters
[in]objPointer to data path object
Return values
NONE

Definition at line 5146 of file dss_data_path.c.

◆ populateOutputs()

void populateOutputs ( DSS_DataPathObj obj)

◆ pruneToPeaks()

uint32_t pruneToPeaks ( uint16_t *restrict  cfarDetObjIndexBuf,
uint16_t *restrict  cfarDetObjSNR,
uint32_t  numDetObjPerCfar,
uint16_t *restrict  sumAbs,
uint16_t  numBins 
)

Description
This function pruneToPeaks selects the peaks from within the list of objects detected by CFAR.

Parameters
[in,out]cfarDetObjIndexBufThe indices of the detected objects.
[in,out]cfarDetObjSNRThe SNR of the detected objects.
[in]numDetObjPerCfarThe number of detected objects.
[in]sumAbsThe sumAbs array on which the CFAR was run.
Return values
Thenumber of detected objects that are peaks.

Definition at line 3208 of file dss_data_path.c.

◆ pruneToPeaksOrNeighbourOfPeaks()

uint32_t pruneToPeaksOrNeighbourOfPeaks ( uint16_t *restrict  cfarDetObjIndexBuf,
uint16_t *restrict  cfarDetObjSNR,
uint32_t  numDetObjPerCfar,
uint16_t *restrict  sumAbs,
uint16_t  numBins 
)

Description
A slightly weaker implementation of the 'pruneToPeaks' algorithm. This variation passes peaks as well as their largest neighbour.

Parameters
[in,out]cfarDetObjIndexBufThe indices of the detected objects.
[in,out]cfarDetObjSNRThe SNR of the detected objects.
[in]numDetObjPerCfarThe number of detected objects.
[in]sumAbsThe sumAbs array on which the CFAR was run.
[in]numBinsThe length of the sumAbs array.
Return values
NONE

Definition at line 5173 of file dss_data_path.c.

◆ pruneTrackingInput()

uint32_t pruneTrackingInput ( trackingInputReport_t trackingInput,
const uint32_t  numCluster 
)

Description
The function removes objects from extreme angles and with poor angle SNR from the tracking input.

Parameters
[in]trackinginputList of tracking inputs.
[in]numClustersnumber of tracking inputs (from the clustering output).
Return values
numberof tracking inputs after pruning.

Definition at line 4706 of file dss_data_path.c.

◆ quadraticInterpFltPeakLoc()

float quadraticInterpFltPeakLoc ( float *restrict  y,
int32_t  len,
int32_t  indx 
)

Description
The function performs a quadractic peak interpolation to compute the fractional offset of the peak location. It is primarily intended to be used in oversampled FFTs.

Parameters
[in]ythe array of data.
[in]lenlength of the array.
[in]indxcoarse peak location.
Return values
interpolatedpeak location (varies from -1 to +1).

Definition at line 4741 of file dss_data_path.c.

◆ quadraticInterpLog2ShortPeakLoc()

float quadraticInterpLog2ShortPeakLoc ( uint16_t *restrict  y,
int32_t  len,
int32_t  indx,
uint16_t  fracBitIn 
)

Description
The function performs a quadractic peak interpolation to compute the fractional offset of the peak location. It is primarily intended to be used in oversampled FFTs. The input is assumed to be an unsigned short.

Parameters
[in]ythe array of data.
[in]lenlength of the array.
[in]indxcoarse peak location.
[in]fracBitInfractional bits in the input array.
Return values
interpolatedpeak location (varies from -1 to +1).

Definition at line 4795 of file dss_data_path.c.

◆ rangeBasedPruning()

uint32_t rangeBasedPruning ( MmwDemo_detectedObjActual *restrict  objOut,
MmwDemo_objRaw2D_t *restrict  objRaw,
RangeDependantThresh_t *restrict  SNRThresh,
RangeDependantThresh_t *restrict  peakValThresh,
uint32_t  numDetectedObjects,
uint32_t  numDopplerBins,
uint32_t  maxRange,
uint32_t  minRange 
)

Description
This function populates the ObjOut based on the objRaw. It includes one more layer of pruning which prevent objects beyond the maximum range or minimum range from being populated. Additionally we change the SNR requirement as a function of the range, requiring larger SNR for objects closer to the car, and lower SNR for objects farther from the car.

Parameters
[out]objOutOutput array of detected objects after peak grouping
[in]objRawArray of detected objects after CFAR detection
[in]SNRThreshA list of SNR thresholds for a list of ranges.
[in]SNRThreshA list of peakVal thresholds for a list of ranges.
[in]numDetectedObjectsNumber of detected objects by CFAR
[in]numDopplerBinsNumber of Doppler bins
[in]maxRangeMaximum range (in ONE_QFORMAT)
[in]minRangeMinimum range (in ONE_QFORMAT)
Return values
Numberof detected objects after grouping

Definition at line 1317 of file dss_data_path.c.

◆ secondDimFFTandLog2Computation() [1/2]

uint32_t secondDimFFTandLog2Computation ( DSS_DataPathObj obj,
uint16_t *  sumAbs,
uint16_t  checkDetMatrixTx,
uint16_t  rangeIdx,
uint32_t *  pingPongIdxPtr 
)

◆ secondDimFFTandLog2Computation() [2/2]

uint32_t secondDimFFTandLog2Computation ( DSS_DataPathObj *restrict  obj,
uint16_t *restrict  sumAbs,
uint16_t  checkDetMatrixTx,
uint16_t  rangeIdx,
uint32_t *  pingPongIdxPtr 
)

Description
Function to perform 2D-FFT on all Rxs corresponding to one range gatewindow sample. Following the FFT it computes the Log2 Abs and optionally stores it in detMatrix.

Parameters
[in,out]objData path object.
[out]sumAbsSum of the log2 of absolute value.
[in]checkDetMatrixTxOptionally check whether the detection matrix has been transferred to L3.
[in]rangeIdxThe index of the range gate being processed.
[in,out]pingPongIdxPtrPointer to the current ping-pong indx
Return values
waitingTime.

Definition at line 2926 of file dss_data_path.c.

◆ select_channel()

uint8_t select_channel ( uint8_t  subframeIndx,
uint8_t  pingPongId,
uint8_t  option0ping,
uint8_t  option0pong 
)

Description
selects one of four channels based on the subframe and the 'ping pong' ID

Definition at line 266 of file dss_data_path.c.

References pingPongId.

Referenced by MmwDemo_dataPathWait1DOutputData(), MmwDemo_dataPathWait2DInputData(), and MmwDemo_dataPathWait3DInputData().

Here is the caller graph for this function:

Variable Documentation

◆ gCycleLog

volatile cycleLog_t gCycleLog

Definition at line 99 of file dss_main.c.

Referenced by MmwDemo_processChirp().

◆ gMCB

MCB gMCB

Global Variable for tracking information required by the design.

Definition at line 97 of file dss_main.c.

◆ gMmwL1

uint8_t gMmwL1[MMW_L1_HEAP_SIZE]

L1 Heap

Definition at line 136 of file dss_data_path.c.

◆ gMmwL2

uint8_t gMmwL2[MMW_L2_HEAP_SIZE]

L2 Heap

Definition at line 131 of file dss_data_path.c.

◆ gMmwL3

uint8_t gMmwL3[SOC_XWR18XX_DSS_L3RAM_SIZE]

L3 RAM buffer

Definition at line 126 of file dss_data_path.c.

ALIGN
#define ALIGN(x, a)