![]() |
TI-radar AWR1843 C674x DSP core
1
|
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"
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 |
Implements Data path processing functionality.
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.
#define ALIGN | ( | x, | |
a | |||
) | (((x)+((a)-1))&~((a)-1)) |
#define DebugP_ASSERT_ENABLED 1 |
Definition at line 70 of file dss_data_path.c.
#define EIGHTEEN_DB_DOPPLER_SNR ((18 *(256))/6) |
Definition at line 4449 of file dss_data_path.c.
#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.
#define FFT_WINDOW_INT32 1 |
FFT window 32 - samples format is int32_t
Definition at line 142 of file dss_data_path.c.
#define FOUR_POINT_ZERO_METERS (4 * 128) |
Definition at line 4451 of file dss_data_path.c.
#define isPong | ( | x | ) | (pingPongId(x)) |
Definition at line 159 of file dss_data_path.c.
#define MMW_ADCBUF_SIZE 0x4000U |
Definition at line 113 of file dss_data_path.c.
#define MMW_ALLOC_BUF | ( | name, | |
nameType, | |||
startAddr, | |||
alignment, | |||
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.
#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.
#define MMW_WIN_BLACKMAN 1 |
Blackman window
Definition at line 148 of file dss_data_path.c.
#define MMW_WIN_HAMMING 0 |
Hamming window
Definition at line 146 of file dss_data_path.c.
#define MMW_WIN_HANNING_RECT 3 |
rectangularized Hanning window
Definition at line 152 of file dss_data_path.c.
#define MMW_WIN_RECT 2 |
Rectangular window
Definition at line 150 of file dss_data_path.c.
#define pingPongId | ( | x | ) | ((x) & 0x1U) |
Definition at line 158 of file dss_data_path.c.
#define ROUND | ( | x | ) | ((x) < 0 ? ((x) - 0.5) : ((x) + 0.5) ) |
Definition at line 109 of file dss_data_path.c.
#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.
#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.
[in,out] | obj | data path object. |
na. |
Definition at line 2329 of file dss_data_path.c.
#define SOC_MAX_NUM_TX_ANTENNAS 3 |
Definition at line 2330 of file dss_data_path.c.
#define SOC_XWR18XX_DSS_L3RAM_SIZE 0x100000 |
Definition at line 111 of file dss_data_path.c.
#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.
[in] | obj | data path object. |
none |
Definition at line 4448 of file dss_data_path.c.
#define ZERO_POINT_FIVE_METERS (0.5f * 128) |
Definition at line 4450 of file dss_data_path.c.
float antilog2 | ( | int32_t | inputActual, |
uint16_t | fracBitIn | ||
) |
Description
The function computes an antilog2 on the input which has a0 specified bitwidth.
[in] | input | 16 bit input with specified bitwidth. |
[in] | fracBitIn | input fractional bitwidth. |
2^(input/(2^fracBitIn)) |
Definition at line 4037 of file dss_data_path.c.
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.
[in] | output | The output of the clustering algorithm. |
[in] | state | The previous clustering output. |
[in] | maxNumTrackers | The maximum number of trackers. |
[in] | epsilon2 | distance metric param for association. |
none |
Definition at line 4322 of file dss_data_path.c.
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.
[in] | input | data path object. |
none |
Azimuth calculation
Definition at line 4059 of file dss_data_path.c.
void calc_cmplx_exp | ( | cmplx16ImRe_t * | dftSinCos, |
float | i, | ||
uint32_t | dftLen | ||
) |
Definition at line 2090 of file dss_data_path.c.
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.
[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 |
Definition at line 3546 of file dss_data_path.c.
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.
[in,out] | sumAbs | The slow chirps doppler bins at a certain range. |
[in] | fastChirpVel | The velocity estimate using the fast chirps (pre-disambiguation). |
[in] | fastChirpPeakVal | The peak value of the index of the detected object from the fast chirp. |
[in] | obj | data path object. |
Ambiguity | index. |
[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 |
Definition at line 3400 of file dss_data_path.c.
uint32_t cfarPeakGroupingAlongDoppler | ( | MmwDemo_objRaw2D_t *restrict | objOut, |
uint32_t | numDetectedObjects, | ||
uint16_t * | detMatrix, | ||
uint32_t | numRangeBins, | ||
uint32_t | numDopplerBins | ||
) |
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.
[out] | objOut | Output array of detected objects after peak grouping |
[in] | objRaw | Array of detected objects after CFAR detection |
[in] | numDetectedObjects | Number of detected objects by CFAR |
[in] | detMatrix | Detection Range/Doppler matrix |
[in] | numDopplerBins | Number of Doppler bins3401 |
Number | of detected objects after grouping |
Definition at line 3845 of file dss_data_path.c.
uint16_t computeSinAzimSNR | ( | float * | azimuthMagSqr, |
uint16_t | azimIdx, | ||
uint16_t | numVirtualAntAzim, | ||
uint16_t | numAngleBins, | ||
uint16_t | xyzOutputQFormat | ||
) |
Description
The function
[out] | azimuthMagSqr | Input array of the sum of the squares of the zero padded FFT output. |
[in] | azimIdx | The location of the peak of the detected object. |
[in] | numVirtualAntAzim | the size of the FFT input. |
[in] | numAngleBins | The size of the FFT output. |
[in] | xyzOutputQFormat | number of fractional bits in the output. |
SNRlinear | with the programmed fractional bitwidth |
Definition at line 3919 of file dss_data_path.c.
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.
[in] | SNRdB | 16 bit input with specified bitwidth. |
[in] | bitW | input fractional bitwidth (for SNR in dB). |
[in] | n_samples | number of samples per chirp. |
[in] | resolution | range resolution in meters. |
CRLB | in the specified resolution (with some lower bounds). |
Definition at line 3971 of file dss_data_path.c.
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.
[in] | SNRdB | 16 bit input with specified bitwidth. |
[in] | bitW | input fractional bitwidth. |
[in] | n_samples | number of samples per chirp. |
[in] | resolution | resolution in meters. |
2^(input/(2^fracBitIn)) |
Definition at line 4008 of file dss_data_path.c.
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
[in,out] | obj | data path object. |
[in] | numDetObjPerCfar | number of detected objects from the CFAR function. |
[in] | dopplerLine | The index of the doppler gate being processed. |
[in] | numDetObj2D | The total number of detected objects. |
[in] | sumAbsRange | The sumAbs Array for the range dimension. It is used to populate the 'peakVal' on a per object basis. |
The | total number of detected objects (including the results of the current intersection). |
Definition at line 3130 of file dss_data_path.c.
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.
[in,out] | obj | data path object. |
[in] | numDetObjPerCfar | number of detected objects from the CFAR function. |
[in] | dopplerLine | The index of the doppler gate being processed. |
[in] | numDetObj2D | The total number of detected objects. |
[in] | sumAbsRange | The sumAbs Array for the range dimension. It is used to populate the 'peakVal' on a per object basis. |
The | total number of detected objects (including the results of the current intersection). |
Definition at line 3031 of file dss_data_path.c.
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.
[in,out] | cfarDetObjIndexBuf | The indices of the detected objects. |
[in,out] | cfarDetObjSNR | The SNR of the detected objects. |
[in] | numDetObjPerCfar | The number of detected objects. |
[in] | sumAbs | The sumAbs array on which the CFAR was run. |
[in] | numBins | The length of the cfarDetObjSNR and cfarDetObjIndexBuf array. |
[in] | K | The maximum number of objects to be returned by this function. |
min(K,numDetObjPerCfar). |
Definition at line 3276 of file dss_data_path.c.
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.
[in] | dopplerIdx | : Doppler index of the object |
[in] | numDopplerBins | : Number of Doppler bins |
[in] | azimuthModCoefs | Table 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 |
Definition at line 4866 of file dss_data_path.c.
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.
[out] | objOut | Output array of detected objects after peak grouping |
[in] | objRaw | Array of detected objects after CFAR detection |
[in] | numDetectedObjects | Number of detected objects by CFAR |
[in] | detMatrix | Detection Range/Doppler matrix |
[in] | numDopplerBins | Number of Doppler bins |
[in] | groupInDopplerDirection | Flag enables grouping in Doppler directiuon |
[in] | groupInRangeDirection | Flag enables grouping in Range directiuon |
Number | of detected objects after grouping |
Definition at line 3710 of file dss_data_path.c.
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.
Not | Applicable. |
Definition at line 2331 of file dss_data_path.c.
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.
[in] | obj | Pointer to data path object array. |
-1 | if 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.
void MmwDemo_dataPathConfigFFTs | ( | DSS_DataPathObj * | obj | ) |
Description
Function to populate the twiddle factors for FFTS needed for the data path object.
[in,out] | obj | data path object. |
waitingTime. |
Definition at line 2746 of file dss_data_path.c.
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.
[in,out] | obj | data path object. |
success. |
Definition at line 2272 of file dss_data_path.c.
void MmwDemo_dataPathInit1Dstate | ( | DSS_DataPathObj * | obj | ) |
Description
This function initializes some of the states (counters) used for 1D processing.
[in,out] | obj | data path object. |
success/failure. |
Definition at line 2198 of file dss_data_path.c.
int32_t MmwDemo_dataPathInitEdma | ( | DSS_DataPathObj * | obj | ) |
Description
This function copies the EDMA handles to all of the remaining data path objects.
[in,out] | obj | data path object. |
success/failure. |
Definition at line 2223 of file dss_data_path.c.
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.
[in] | obj | Pointer to data path object |
[in] | pingPongId | ping-pong id (ping is 0 and pong is 1) |
[in] | subframeIndx |
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.
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.
[in] | obj | Pointer to data path object |
[in] | pingPongId | ping-pong id (ping is 0 and pong is 1) |
[in] | subframeIndx |
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().
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.
[in] | obj | Pointer to data path object |
[in] | pingPongId | ping-pong id (ping is 0 and pong is 1) |
[in] | subframe | Index |
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().
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.
[in] | obj | Pointer to data path object |
[in] | pingPongId | ping-pong id (ping is 0 and pong is 1) |
[in] | subframeIndx |
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().
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.
[in] | obj | Pointer to data path object |
[in] | subframeIndx |
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.
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.
[in] | obj | Pointer to data path object |
[in] | subframeIndx |
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.
void MmwDemo_dcRangeSignatureCompensation | ( | DSS_DataPathObj * | obj, |
uint8_t | chirpPingPongId | ||
) |
Description
Compensation of DC range antenna signature (unused currently)
Not | Applicable. |
Definition at line 1447 of file dss_data_path.c.
void MmwDemo_edmaErrorCallbackFxn | ( | EDMA_Handle | handle, |
EDMA_errorInfo_t * | errorInfo | ||
) |
Description
This is a callback function for EDMA errors.
[in] | handle | EDMA Handle. |
[in] | errorInfo | EDMA error info. |
n/a. |
Definition at line 2163 of file dss_data_path.c.
void MmwDemo_edmaTransferControllerErrorCallbackFxn | ( | EDMA_Handle | handle, |
EDMA_transferControllerErrorInfo_t * | errorInfo | ||
) |
Description
This is a callback function for EDMA TC errors.
[in] | handle | EDMA Handle. |
[in] | errorInfo | EDMA TC error info. |
n/a. |
Definition at line 2178 of file dss_data_path.c.
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]
[out] | dftSinCosTable | Array with generated Sin Cos table |
[out] | dftHalfBinVal | Sin/Cos value at half the bin |
[in] | dftLen | Length of the DFT |
Not | Applicable. |
Definition at line 2130 of file dss_data_path.c.
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.
[out] | win | Pointer to calculated window samples. |
[in] | windowDatumType | Window 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] | winLen | Nominal window length |
[in] | winGenLen | Number of generated samples |
[in] | oneQformat | Q format of samples, oneQformat is the value of one in the desired format. |
[in] | winType | Type of window, one of MMW_WIN_BLACKMAN, MMW_WIN_HANNING, or MMW_WIN_RECT. |
none. |
Definition at line 2796 of file dss_data_path.c.
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.
Definition at line 377 of file dss_data_path.c.
References MmwDemo_1D_DopplerLines::currentIndex, and MmwDemo_1D_DopplerLines::dopplerLineMask.
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.
Not | Applicable. |
Definition at line 1562 of file dss_data_path.c.
Referenced by MmwDemo_processChirp().
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.
Not | Applicable. |
Definition at line 1633 of file dss_data_path.c.
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.
Definition at line 352 of file dss_data_path.c.
References MmwDemo_1D_DopplerLines::dopplerLineMask.
void MmwDemo_magnitudeSquared | ( | cmplx32ReIm_t *restrict | inpBuff, |
float *restrict | magSqrdBuff, | ||
uint32_t | numSamples | ||
) |
Description
Outputs magnitude squared float array of input complex32 array
Not | Applicable. |
Definition at line 1428 of file dss_data_path.c.
uint32_t MmwDemo_pow2roundup | ( | uint32_t | x | ) |
Description
Power of 2 round up function.
Definition at line 404 of file dss_data_path.c.
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.
[in,out] | obj | data path object. |
na. |
Definition at line 2297 of file dss_data_path.c.
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.
Not | Applicable. |
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.
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.
|
inlinestatic |
Function Name : MmwDemo_rxChanPhaseBiasCompensation.
[in] | rxChComp | : rx channel compensation coefficient |
[in] | input | : 32-bit complex input symbols must be 64 bit aligned |
[in] | numAnt | : number of symbols |
Definition at line 4939 of file dss_data_path.c.
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.
Definition at line 336 of file dss_data_path.c.
References MmwDemo_1D_DopplerLines::dopplerLineMask.
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.
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.
Not | Applicable. |
Definition at line 2079 of file dss_data_path.c.
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.
[in] | obj | Pointer to data path object |
[in] | objIndex | Detected object index |
[in] | azimIdx | Index of the peak position in Azimuth FFT output |
[in] | azimuthMagSqr | azimuth energy array |
NONE |
Definition at line 4982 of file dss_data_path.c.
Referenced by 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.
[in] | obj | Pointer to data path object |
[in] | objIndex | Detected object index |
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.
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.
[in] | obj | Pointer to data path object |
[in] | objIndex | Detected object index |
[in] | azimIdx | Index of the peak position in Azimuth FFT output |
[in] | azimuthMagSqr | azimuth energy array |
NONE |
Definition at line 5052 of file dss_data_path.c.
Referenced by 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.
[in] | obj | Pointer to data path object |
[in] | objIndex | Detected object index |
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.
void parkingAssistInit | ( | DSS_DataPathObj * | obj | ) |
Description
Initialize the 'parking assist bins' state which is essentially the closest obstruction upper bounded by its maximum value.
[in] | obj | Pointer to data path object |
NONE |
Definition at line 5146 of file dss_data_path.c.
void populateOutputs | ( | DSS_DataPathObj * | obj | ) |
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 by populating new structure which hold only the minimum information necessary for the GUI.
[in] | input | data path object. |
none |
Definition at line 4452 of file dss_data_path.c.
References AGED_OBJ_DELETION_THRESH, DSS_DataPathObj_t::clusterOpFinal, DSS_DataPathObj_t::dbScanInstance, DSS_DataPathObj_t::dbScanReport, DSS_DataPathObj_t::dbScanState, DSS_DataPathObj_t::detObj2D, DSS_DataPathObj_t::detObjFinal, EIGHTEEN_DB_DOPPLER_SNR, FOUR_POINT_ZERO_METERS, iX, iXd, iY, iYd, MAX_VEL_ENH_PROCESSING, clusteringDBscanInstance::maxClusters, KFtrackerInstance::maxTrackers, MIN_TICK_FOR_TX, MmwDemo_dssAssert, DSS_DataPathObj_t::numActiveTrackers, clusteringDBscanOutput::numCluster, DSS_DataPathObj_t::numDetObj, DSS_DataPathObj_t::parkingAssistBins, DSS_DataPathObj_t::parkingAssistBinsState, DSS_DataPathObj_t::parkingAssistBinsStateCnt, DSS_DataPathObj_t::parkingAssistMaxRange, DSS_DataPathObj_t::parkingAssistNumBins, DSS_DataPathObj_t::parkingAssistNumBinsLog2, POINT_CLOUD_PROCESSING, DSS_DataPathObj_t::processingPath, DSS_DataPathObj_t::sinAzimQFormat, DSS_DataPathObj_t::trackerInstance, DSS_DataPathObj_t::trackerOpFinal, DSS_DataPathObj_t::trackerState, TWENTY_TWO_DB_DOPPLER_SNR, KFstate::vec, KFstate::xSize, DSS_DataPathObj_t::xyzOutputQFormat, KFstate::ySize, and ZERO_POINT_FIVE_METERS.
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.
[in,out] | cfarDetObjIndexBuf | The indices of the detected objects. |
[in,out] | cfarDetObjSNR | The SNR of the detected objects. |
[in] | numDetObjPerCfar | The number of detected objects. |
[in] | sumAbs | The sumAbs array on which the CFAR was run. |
The | number of detected objects that are peaks. |
Definition at line 3208 of file dss_data_path.c.
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.
[in,out] | cfarDetObjIndexBuf | The indices of the detected objects. |
[in,out] | cfarDetObjSNR | The SNR of the detected objects. |
[in] | numDetObjPerCfar | The number of detected objects. |
[in] | sumAbs | The sumAbs array on which the CFAR was run. |
[in] | numBins | The length of the sumAbs array. |
NONE |
Definition at line 5173 of file dss_data_path.c.
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.
[in] | trackinginput | List of tracking inputs. |
[in] | numClusters | number of tracking inputs (from the clustering output). |
number | of tracking inputs after pruning. |
Definition at line 4706 of file dss_data_path.c.
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.
[in] | y | the array of data. |
[in] | len | length of the array. |
[in] | indx | coarse peak location. |
interpolated | peak location (varies from -1 to +1). |
Definition at line 4741 of file dss_data_path.c.
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.
[in] | y | the array of data. |
[in] | len | length of the array. |
[in] | indx | coarse peak location. |
[in] | fracBitIn | fractional bits in the input array. |
interpolated | peak location (varies from -1 to +1). |
Definition at line 4795 of file dss_data_path.c.
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.
[out] | objOut | Output array of detected objects after peak grouping |
[in] | objRaw | Array of detected objects after CFAR detection |
[in] | SNRThresh | A list of SNR thresholds for a list of ranges. |
[in] | SNRThresh | A list of peakVal thresholds for a list of ranges. |
[in] | numDetectedObjects | Number of detected objects by CFAR |
[in] | numDopplerBins | Number of Doppler bins |
[in] | maxRange | Maximum range (in ONE_QFORMAT) |
[in] | minRange | Minimum range (in ONE_QFORMAT) |
Number | of detected objects after grouping |
Definition at line 1317 of file dss_data_path.c.
uint32_t secondDimFFTandLog2Computation | ( | DSS_DataPathObj * | obj, |
uint16_t * | sumAbs, | ||
uint16_t | checkDetMatrixTx, | ||
uint16_t | rangeIdx, | ||
uint32_t * | pingPongIdxPtr | ||
) |
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.
[in,out] | obj | Data path object. |
[out] | sumAbs | Sum of the log2 of absolute value. |
[in] | checkDetMatrixTx | Optionally check whether the detection matrix has been transferred to L3. |
[in] | rangeIdx | The index of the range gate being processed. |
[in,out] | pingPongIdxPtr | Pointer to the current ping-pong indx |
waitingTime. |
Definition at line 2926 of file dss_data_path.c.
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().
volatile cycleLog_t gCycleLog |
Definition at line 99 of file dss_main.c.
Referenced by MmwDemo_processChirp().
MCB gMCB |
Global Variable for tracking information required by the design.
Definition at line 97 of file dss_main.c.
uint8_t gMmwL1[MMW_L1_HEAP_SIZE] |
L1 Heap
Definition at line 136 of file dss_data_path.c.
uint8_t gMmwL2[MMW_L2_HEAP_SIZE] |
L2 Heap
Definition at line 131 of file dss_data_path.c.
uint8_t gMmwL3[SOC_XWR18XX_DSS_L3RAM_SIZE] |
L3 RAM buffer
Definition at line 126 of file dss_data_path.c.