 |
TI-radar AWR1843 C674x DSP core
1
|
Go to the documentation of this file.
28 #include <xdc/cfg/global.h>
29 #include <xdc/runtime/IHeap.h>
30 #include <xdc/runtime/System.h>
31 #include <xdc/runtime/Error.h>
32 #include <xdc/runtime/Memory.h>
33 #include <ti/sysbios/BIOS.h>
34 #include <ti/sysbios/knl/Task.h>
35 #include <ti/sysbios/knl/Event.h>
36 #include <ti/sysbios/knl/Semaphore.h>
37 #include <ti/sysbios/knl/Clock.h>
38 #include <ti/sysbios/heaps/HeapBuf.h>
39 #include <ti/sysbios/heaps/HeapMem.h>
40 #include <ti/sysbios/knl/Event.h>
41 #include <ti/sysbios/family/c64p/Cache.h>
42 #include <ti/sysbios/family/c64p/Hwi.h>
43 #include <ti/sysbios/family/c64p/EventCombiner.h>
44 #include <ti/sysbios/utils/Load.h>
47 #include <ti/common/sys_common.h>
48 #include <ti/common/mmwave_sdk_version.h>
49 #include <ti/utils/cycleprofiler/cycle_profiler.h>
52 #include <ti/drivers/mailbox/mailbox.h>
53 #include <ti/drivers/adcbuf/ADCBuf.h>
54 #include <ti/drivers/esm/esm.h>
55 #include <ti/drivers/pinmux/pinmux.h>
56 #include <ti/drivers/soc/soc.h>
75 #define SOC_XWR18XX_DSS_HSRAM_SIZE 0x8000U
78 #define DATAPATH_DET_PAYLOAD_SIZE (SOC_XWR18XX_DSS_HSRAM_SIZE - sizeof(uint8_t))
84 #pragma DATA_SECTION(gHSRAM, ".appSharedMem");
85 #pragma DATA_ALIGN(gHSRAM, 4);
89 #define MMW_NUM_ANGLE_BINS 64
90 #define SPEED_OF_LIGHT_IN_METERS_PER_SEC (3.0e8)
91 #define SPEED_OF_LIGHT_IN_METERS_PER_USEC (3.0e2)
119 static void DSS_edmaBlockCopy(EDMA_Handle handle, uint32_t loadAddr, uint32_t runAddr, uint16_t size);
120 static void DSS_copyTable(EDMA_Handle handle, COPY_TABLE *tp);
203 volatile uint32_t startTime;
242 startTime = Cycleprofiler_getTimeStamp();
311 nameSize = strlen(file);
319 System_printf (
"Error: Failed to send exception information to MSS.\n");
334 Task_Params taskParams;
340 memset((
void*) &
gMCB, 0,
sizeof(
MCB));
368 memset((
void *) &socCfg, 0,
sizeof(SOC_Cfg));
371 socCfg.clockCfg = SOC_SysClock_BYPASS_INIT;
384 Task_Params_init(&taskParams);
385 taskParams.stackSize = 3 * 1024;
477 Mailbox_Config mboxCfg;
478 Task_Params taskParams;
484 Mailbox_init (MAILBOX_TYPE_DSS);
488 ADCBuf_Params adcBufParams;
495 ADCBuf_Params_init(&adcBufParams);
496 adcBufParams.chirpThresholdPing = 1;
497 adcBufParams.chirpThresholdPong = 1;
498 adcBufParams.continousMode = 0;
514 SOC_SysIntListenerCfg listenerCfg;
517 memset((
void*) &listenerCfg, 0,
sizeof(SOC_SysIntListenerCfg));
518 listenerCfg.systemInterrupt = SOC_XWR18XX_DSS_INTC_EVENT_CHIRP_AVAIL;
528 memset((
void*) &listenerCfg, 0,
sizeof(SOC_SysIntListenerCfg));
529 listenerCfg.systemInterrupt = SOC_XWR18XX_DSS_INTC_EVENT_FRAME_START;
541 Mailbox_Config_init(&mboxCfg);
544 mboxCfg.chType = MAILBOX_CHTYPE_MULTI;
545 mboxCfg.chId = MAILBOX_CH_ID_0;
546 mboxCfg.writeMode = MAILBOX_MODE_BLOCKING;
547 mboxCfg.readMode = MAILBOX_MODE_CALLBACK;
550 gMCB.
mboxHandle = Mailbox_open(MAILBOX_TYPE_MSS, &mboxCfg, &errCode);
596 Task_Params_init(&taskParams);
597 taskParams.priority = 2;
598 taskParams.stackSize = 4 * 1024;
618 #ifdef SUBFRAME_CONF_MRR_USRR
619 DSS_populateMRR(obj, 0);
622 #ifdef SUBFRAME_CONF_MRR
623 DSS_populateMRR(obj, 0);
625 #ifdef SUBFRAME_CONF_USRR
684 else if (retVal == 0)
696 switch (message.
type)
700 uint8_t prevSubframeIndx;
770 uint32_t outputBufSize,
773 uint8_t *ptrCurrBuffer;
774 uint32_t totalHsmSize = 0;
776 uint32_t itemPayloadLen;
783 ptrCurrBuffer = ptrHsmBuffer;
786 memset((
void *) &message, 0,
sizeof(
mmWaveMSG));
790 message.body.detObj.header.platform = 0xA1642 ;
791 message.body.detObj.header.magicWord[0] = 0x0102;
792 message.body.detObj.header.magicWord[1] = 0x0304;
793 message.body.detObj.header.magicWord[2] = 0x0506;
794 message.body.detObj.header.magicWord[3] = 0x0708;
795 message.body.detObj.header.numDetectedObj = obj->
numDetObj;
796 message.body.detObj.header.version = MMWAVE_SDK_VERSION_BUILD | (MMWAVE_SDK_VERSION_BUGFIX << 8) | (MMWAVE_SDK_VERSION_MINOR << 16) | (MMWAVE_SDK_VERSION_MAJOR << 24);
806 totalHsmSize += itemPayloadLen;
807 if (totalHsmSize > outputBufSize)
812 memcpy(ptrCurrBuffer, (
void *) &descr, itemPayloadLen);
816 totalHsmSize += itemPayloadLen;
817 if (totalHsmSize > outputBufSize)
825 message.body.detObj.tlv[tlvIdx].length = itemPayloadLen
827 message.body.detObj.tlv[tlvIdx].type =
829 message.body.detObj.tlv[tlvIdx].address = (uint32_t) ptrCurrBuffer;
833 ptrCurrBuffer += itemPayloadLen
848 totalHsmSize += itemPayloadLen;
849 if (totalHsmSize > outputBufSize)
854 memcpy(ptrCurrBuffer, (
void *) &descr, itemPayloadLen);
858 totalHsmSize += itemPayloadLen;
859 if (totalHsmSize > outputBufSize)
867 message.body.detObj.tlv[tlvIdx].length = itemPayloadLen
869 message.body.detObj.tlv[tlvIdx].type =
871 message.body.detObj.tlv[tlvIdx].address = (uint32_t) ptrCurrBuffer;
875 ptrCurrBuffer += itemPayloadLen
888 totalHsmSize += itemPayloadLen;
889 if (totalHsmSize > outputBufSize)
894 memcpy(ptrCurrBuffer, (
void *) &descr, itemPayloadLen);
898 totalHsmSize += itemPayloadLen;
899 if (totalHsmSize > outputBufSize)
907 message.body.detObj.tlv[tlvIdx].length = itemPayloadLen
909 message.body.detObj.tlv[tlvIdx].type =
911 message.body.detObj.tlv[tlvIdx].address = (uint32_t) ptrCurrBuffer;
915 ptrCurrBuffer += itemPayloadLen
929 totalHsmSize += itemPayloadLen;
930 if (totalHsmSize > outputBufSize)
935 memcpy(ptrCurrBuffer, (
void *) &descr, itemPayloadLen);
939 totalHsmSize += itemPayloadLen;
940 if (totalHsmSize > outputBufSize)
948 message.body.detObj.tlv[tlvIdx].length = itemPayloadLen
950 message.body.detObj.tlv[tlvIdx].type =
952 message.body.detObj.tlv[tlvIdx].address = (uint32_t) ptrCurrBuffer;
968 message.body.detObj.header.numTLVs = tlvIdx;
970 message.body.detObj.header.totalPacketLen =
975 message.body.detObj.header.timeCpuCycles = Cycleprofiler_getTimeStamp();
1000 volatile int32_t waitCounter = 0;
1053 ADCBuf_dataFormat dataFormat;
1054 ADCBuf_RxChanConf rxChanConf;
1058 uint8_t chInterleave;
1059 uint8_t sampleInterleave;
1060 uint32_t chirpThreshold;
1061 uint32_t rxChanMask = 0xF;
1066 sampleInterleave = 0;
1070 offset = ((32 * 1024)/4);
1077 dataFormat.adcOutFormat = adcFmt;
1078 dataFormat.channelInterleave = chInterleave;
1079 dataFormat.sampleInterleave = sampleInterleave;
1083 ADCBufMMWave_CMD_CHANNEL_DISABLE,
1084 (
void *) &rxChanMask)) < 0)
1091 ADCBufMMWave_CMD_CONF_DATA_FORMAT,
1092 (
void *) &dataFormat);
1099 memset((
void*) &rxChanConf, 0,
sizeof(ADCBuf_RxChanConf));
1102 for (channel = 0; channel < SYS_COMMON_NUM_RX_CHANNEL; channel++)
1105 rxChanConf.channel = channel;
1107 ADCBufMMWave_CMD_CHANNEL_ENABLE,
1108 (
void *) &rxChanConf);
1116 rxChanConf.offset += offset;
1121 ADCBufMMWave_CMD_SET_PING_CHIRP_THRESHHOLD,
1122 (
void *) &chirpThreshold);
1129 ADCBufMMWave_CMD_SET_PONG_CHIRP_THRESHHOLD,
1130 (
void *) &chirpThreshold);
1151 static void DSS_copyTable(EDMA_Handle handle, COPY_TABLE *tp)
1158 for (i = 0; i < tp->num_recs; i++)
1161 loadAddr = (uint32_t)crp.load_addr;
1162 runAddr = (uint32_t)crp.run_addr;
1189 static void DSS_edmaBlockCopy(EDMA_Handle handle, uint32_t loadAddr, uint32_t runAddr, uint16_t size)
1191 EDMA_channelConfig_t config;
1192 volatile bool isTransferDone;
1194 config.channelId = EDMA_TPCC0_REQ_FREE_0;
1195 config.channelType = (uint8_t)EDMA3_CHANNEL_TYPE_DMA;
1196 config.paramId = (uint16_t)EDMA_TPCC0_REQ_FREE_0;
1197 config.eventQueueId = 0;
1199 config.paramSetConfig.sourceAddress = (uint32_t) SOC_translateAddress((uint32_t)loadAddr,
1200 SOC_TranslateAddr_Dir_TO_EDMA, NULL);
1201 config.paramSetConfig.destinationAddress = (uint32_t) SOC_translateAddress((uint32_t)runAddr,
1202 SOC_TranslateAddr_Dir_TO_EDMA, NULL);
1204 config.paramSetConfig.aCount = size;
1205 config.paramSetConfig.bCount = 1U;
1206 config.paramSetConfig.cCount = 1U;
1207 config.paramSetConfig.bCountReload = 0U;
1209 config.paramSetConfig.sourceBindex = 0U;
1210 config.paramSetConfig.destinationBindex = 0U;
1212 config.paramSetConfig.sourceCindex = 0U;
1213 config.paramSetConfig.destinationCindex = 0U;
1215 config.paramSetConfig.linkAddress = EDMA_NULL_LINK_ADDRESS;
1216 config.paramSetConfig.transferType = (uint8_t)EDMA3_SYNC_A;
1217 config.paramSetConfig.transferCompletionCode = (uint8_t) EDMA_TPCC0_REQ_FREE_0;
1218 config.paramSetConfig.sourceAddressingMode = (uint8_t) EDMA3_ADDRESSING_MODE_LINEAR;
1219 config.paramSetConfig.destinationAddressingMode = (uint8_t) EDMA3_ADDRESSING_MODE_LINEAR;
1222 config.paramSetConfig.fifoWidth = (uint8_t) EDMA3_FIFO_WIDTH_8BIT;
1224 config.paramSetConfig.isStaticSet =
false;
1225 config.paramSetConfig.isEarlyCompletion =
false;
1226 config.paramSetConfig.isFinalTransferInterruptEnabled =
true;
1227 config.paramSetConfig.isIntermediateTransferInterruptEnabled =
false;
1228 config.paramSetConfig.isFinalChainingEnabled =
false;
1229 config.paramSetConfig.isIntermediateChainingEnabled =
false;
1230 config.transferCompletionCallbackFxn = NULL;
1231 config.transferCompletionCallbackFxnArg = NULL;
1233 if (EDMA_configChannel(handle, &config,
false) != EDMA_NO_ERROR)
1238 if (EDMA_startDmaTransfer(handle, config.channelId) != EDMA_NO_ERROR)
1246 if (EDMA_isTransferComplete(handle,
1247 config.paramSetConfig.transferCompletionCode,
1248 (
bool *)&isTransferDone) != EDMA_NO_ERROR)
1253 while (isTransferDone ==
false);
1256 EDMA_disableChannel(handle, config.channelId, config.channelType);
1273 float scaleFac = (float) ((1 << bitwidth) * numInteg);
1274 float convertFrom_10Log10_to_20Log2 = ThresholdIndB * (1.0f / 6.0f);
1276 return (uint16_t) (scaleFac * convertFrom_10Log10_to_20Log2);
1338 #if (SUBFRAME_USRR_CHIRPTYPE_0_NUM_CHIRPS != SUBFRAME_USRR_CHIRPTYPE_1_NUM_CHIRPS)
1339 #error "the number of chirps in each chirp type is not equal"
1384 #ifdef LOW_THRESHOLD_FOR_USRR
#define MMW_NOISE_AVG_MODE_CFAR_CA
#define PROFILE_USRR_RANGE_RESOLUTION_METERS
Derived parameters.
char file[MMWAVE_MAX_FILE_NAME_SIZE]
file name
cmplx16ImRe_t * rxChPhaseComp
Pointer to the Rx Gain phase compensation params.
EDMA_Handle edmaHandle[2]
Handle of the EDMA driver.
uint32_t chirpIntCounter
Counter which tracks the number of chirp interrupt detected.
uint8_t winLen
CFAR noise avraging window length.
#define MAX_VEL_ENH_PROCESSING
There are two processing paths in the MRR Demo.
#define SOC_XWR18XX_DSS_HSRAM_SIZE
DSS stores the application output and DSS2MSS ISR information (for fast exception signalling) in HSRA...
uint8_t loggingBufferAvailable
! Data Path object
uint8_t noiseDivShift
CFAR cumulative noise sum divisor.
MCB gMCB
Global Variable for tracking information required by the design.
#define MRR_MAX_OBJ_OUT
The maximum number of objects to be send out per frame. This number is upper bounded by the transfer ...
uint16_t minPointsInCluster
uint16_t rangelim
Range (in meters * (1 << xyzOutputQFormat)) upto which the SNR requirement is valid.
uint16_t maxRange
maximum range at which a target is detected ( in xyzOutputQFormat precision).
uint32_t frameStartEvt
Counter which tracks the number of frame start event detected The frame start event is triggered in t...
#define MMW_OUTPUT_MSG_SEGMENT_LEN
Output packet length is a multiple of this value, must be power of 2.
uint32_t detObjLoggingSkip
Counter which tracks the number of times saving detected objects in logging buffer is skipped.
uint16_t minRange
minimum range at which a target is detected ( in xyzOutputQFormat precision).
uint8_t guardLen
CFAR guard length.
clusteringDBscanOutput_t dbScanReport
The dBscan clustering result structures (holds pointers to the result).
void _MmwDemo_dssAssert(int32_t expression, const char *file, int32_t line)
static void DSS_copyTable(EDMA_Handle handle, COPY_TABLE *tp)
mmWaveMSG_body body
message body
Interface the Extended Kalman Filter.
cycleLog_t cycleLog
DSP cycles for chirp and interframe processing and pending on EDMA data transferes.
uint32_t frameStartIntCounter
Counter which tracks the number of frame start interrupt detected.
uint32_t chirpProcessingEndTime
Chirp processing end time.
void MmwDemo_waitEndOfChirps(DSS_DataPathObj *obj, uint8_t subframeIndx)
void rxGainPhaseParam_Init(DSS_DataPathObj *obj)
uint32_t interFrameWaitTime
total wait time for 2D and 3D EDMA data transfer
#define SUBFRAME_USRR_NUM_ANGLE_BINS
Mbox_Handle mboxHandle
! Handle to the SOC Module
struct clusteringDBscanReportForTx_t clusteringDBscanReportForTx
Structure for each cluster information report .
RangeDependantThresh_t SNRThresholds[MAX_NUM_RANGE_DEPENDANT_SNR_THRESHOLDS]
SNR thresholds as a function of range.
#define ADCBUFF_CHIRP_THRESHOLD
Number of chirps to be collected in the ADC buffer, before the chirp available interrupt.
void DSS_dataPathConfigPopulate(DSS_DataPathObj *obj)
uint16_t numVirtualAntAzim
number of virtual azimuth antennas
#define MMW_NOISE_AVG_MODE_CFAR_CASO
uint16_t numDopplerBins
number of doppler bins
uint16_t numAngleBins
number of angle bins
uint8_t dss2MssIsrInfo
data path processing/detection related msg payloads, these msgs are signalled through DSS to MSS mail...
#define DATAPATH_DET_PAYLOAD_SIZE
uint32_t interChirpProcessingTime
total processing time during all chirps in a frame excluding EDMA waiting time
uint8_t log2numVirtAnt
log2 of the number of virtual antennas.
Structure holds information about detected objects. This information is sent in front of the array of...
mbox_message_type type
message type
uint16_t dBScanNeighbourLim
uint16_t numChirpsPerChirpType
number of chirps per chirp type
float maxUnambiguousVel
maximum unambiguous velocity (without algorithmic improvements) in meters/sec
static int32_t DSS_DataPathConfigAdcBuf()
uint8_t chirpThreshold
Chirp Threshold configuration used for ADCBUF driver.
#define MmwDemo_dssAssert(expression)
float rangeResolution
range resolution in meters
int32_t MmwDemo_dataPathInitEdma(DSS_DataPathObj *obj)
volatile cycleLog_t gCycleLog
#define MMWDEMO_OUTPUT_MSG_PARKING_ASSIST
void MmwDemo_dataPathConfigFFTs(DSS_DataPathObj *obj)
struct mmWave_OUT_MSG_stats_dataObjDescr_t mmWave_OUT_MSG_stats_dataObjDescr
Structure holds information about detected objects. This information is sent in front of the array of...
void ekfInit(DSS_DataPathObj *restrict obj)
struct trackingReportForTx_t trackingReportForTx
Structure for tracking report.
uint16_t enabled
enabled flag: 1-enabled 0-disabled
int32_t MmwDemo_dataPathConfigEdma(DSS_DataPathObj *obj)
uint8_t cyclicMode
CFAR 0-cyclic mode disabled, 1-cyclic mode enabled.
trackingReportForTx * trackerOpFinal
Final list of tracked objects for transmission.
uint16_t numTxAntennas
number of transmit antennas
uint16_t numAdcSamples
number of ADC samples
SOC_SysIntListenerHandle frameStartIntHandle
! Handle to the SOC chirp interrupt listener Handle
void DSS_dBScanConfigBuffers(DSS_DataPathObj *obj)
uint16_t * parkingAssistBins
Nearest object as a function of azimuth.
static void DSS_frameStartIntCallback(uintptr_t arg)
clusteringDBscanInstance_t dbScanInstance
The dBscan clustering configuration structure.
uint16_t * dbscanOutputDataIndexArray
Pointer to dBScan index array.
MmwDemo_DSS_STATS stats
! mmw Demo state
uint16_t xyzQFormat
Q format of detected objects x/y/z coordinates.
uint32_t chirpEvt
Counter which tracks the number of chirp event detected The chirp event is triggered in the ISR for c...
uint16_t numActiveTrackers
number of active trackers.
struct MmwDemo_detectedObjForTx_t MmwDemo_detectedObjForTx
Detected object estimated parameters to be transmitted out.
#define MAX_NUM_CLUSTER_USRR
The maximum number of clusters out of the dbscan algorithm (for the USRR subframe).
MmwDemo_CfarCfg cfarCfgRange
CFAR configuration in Range direction.
void mboxCallbackFxn_MSS_ch0(Mbox_Handle handle, Mailbox_Type peer)
uint16_t cfarCfgRange_minIndxToIgnoreHPF
The HPF can mess up the noise floor computation. So for a certain number of indices,...
uint16_t txAntennaCount
chirp counter modulo number of tx antennas
uint16_t numDetObj
Number of detected objects.
uint8_t sinAzimQFormat
Q format of the sin of the azimuth.
clusteringDBscanReport_t * dbscanOutputDataReport
Pointer to dBScan output Report array.
uint32_t interFrameProcessingEndTime
Inter frame processing end time.
uint32_t interFrameProcessingTime
total processing time for 2D and 3D excluding EDMA waiting time
uint16_t thresholdScale
CFAR threshold scale.
uint16_t numDetetedObj
Number of detected objects.
#define SUBFRAME_USRR_NUM_VIRT_ANT
clusteringDBscanReport_t * report
float velResolution
velocity resolution in meters/sec
#define ROUND_TO_INT32(X)
uint32_t detObjLoggingErr
Counter which tracks the number of times saving detected objects in logging buffer has an error.
MmwDemo_detectedObjForTx * detObjFinal
Final list of detected object for transmission.
#define MMWDEMO_OUTPUT_MSG_CLUSTERS
Message ID for the custom messages from the MRR demo.
uint32_t transmitOutputCycles
time to transmit out detection information (in DSP cycles)
uint16_t convertSNRdBtoThreshold(uint16_t numInteg, float ThresholdIndB, uint16_t bitwidth)
uint16_t numRangeBins
number of range bins
static void DSS_mmWaveCtrlTask(UArg arg0, UArg arg1)
uint8_t xyzOutputQFormat
Q format of the output x/y/z coordinates.
float invOneSinAzimFormat
inverse of the oneQformat
SOC_SysIntListenerHandle chirpIntHandle
! Semaphore handle for the mailbox communication
static void DSS_mmWaveInitTASK(UArg arg0, UArg arg1)
static void mboxIn_uartOut_TASK()
static void DSS_chirpIntCallback(uintptr_t arg)
#define SUBFRAME_USRR_MAX_VEL_M_P_S
uint8_t * dBscanScratchPad
Pointer to dBScan scratch pad.
MmwDemo_CalibDcRangeSigCfg calibDcRangeSigCfg
DC Range antenna signature callibration configuration.
void MmwDemo_interFrameProcessing(DSS_DataPathObj *obj, uint8_t subframeIndx)
#define SUBFRAME_USRR_CHIRPTYPE_0_NUM_CHIRPS
float invOneQFormat
inverse of the oneQformat
uint8_t frameProcToken
! 'mailbox has a message' token
#define POINT_CLOUD_PROCESSING
void MmwDemo_dataPathConfigBuffers(DSS_DataPathObj *objIn, uint32_t adcBufAddress)
void MmwDemo_processChirp(DSS_DataPathObj *obj, uint8_t subframeIndx)
static int32_t DSS_mboxWrite(mmWaveMSG *message)
far COPY_TABLE _MmwDemo_fastCode_L1PSRAM_copy_table
#define CFARTHRESHOLD_N_BIT_FRAC
Fractional bit width for Thresholds for CFAR data (rangeSNRdB, dopplerSNRdB, AzimSNR,...
DSP-Subsystem (DSS) Master control block (MCB) The structure is used to hold handling information,...
uint8_t processingPath
Processing path - either point-cloud or max-vel enhancement.
uint32_t interChirpWaitTime
total wait time for EDMA data transfer during all chirps in a frame
uint16_t threshold
SNR threshold (dB) for the range.
#define MMWDEMO_OUTPUT_MSG_TRACKED_OBJECTS
void MmwDemo_dataPathInit1Dstate(DSS_DataPathObj *obj)
DSS_DataPathObj dataPathObj[NUM_SUBFRAMES]
! mmw Demo statistics
#define SUBFRAME_USRR_VEL_RESOLUTION_M_P_S
Millimeter Wave Demo Data Path Information.
MmwDemo_CfarCfg cfarCfgDoppler
CFAR configuration in Doppler direction.
struct DSS2MSS_HSRAM DSS2MSS_HSRAM_t
clusteringDBscanReportForTx * clusterOpFinal
Final list of clusters for transmission.
float invNumAngleBins
inverse of the numAngleBins
RangeDependantThresh_t peakValThresholds[MAX_NUM_RANGE_DEPENDANT_SNR_THRESHOLDS]
SNR thresholds as a function of range.
The structure defines the message structure used for communication between MSS and DSS.
uint8_t subframeIndx
! Logging buffer flag
DSP cycle profiling structure to accumulate different processing times in chirp and frame processing ...
MmwDemo_MultiObjBeamFormingCfg multiObjBeamFormingCfg
Multi object beam forming configuration.
void DSS_populateUSRR(DSS_DataPathObj *obj, uint16_t subframeIndx)
static int32_t DSS_SendProcessOutputToMSS(uint8_t *ptrHsmBuffer, uint32_t outputBufSize, DSS_DataPathObj *obj)
uint32_t interFrameProcCycles
number of processor cycles between frames excluding processing time to transmit output on UART
uint8_t chirpProcToken
! frame start token
uint16_t numVirtualAntElev
number of virtual elevation antennas
uint8_t log2NumDopplerBins
log 2 of number of doppler bins
static void DSS_DataPathOutputLogging(DSS_DataPathObj *dataPathObj)
#define NUM_RX_CHANNELS
Reduced Thresholds. The following line (if uncommented) reduces thresholds for the USRR detection alg...
uint16_t maxNumObj2DRaw
number of objects to be detected in 2D-CFAR.
uint8_t frameStartIntToken
! inter frameProc token
uint8_t averageMode
CFAR averagining mode 0-CFAR_CA, 1-CFAR_CAGO, 2-CFAR_CASO.
#define MAX_DET_OBJECTS_RAW_POINT_CLOUD_PROCESSING
The maximum number of objects detected in the 'point cloud ' processing path.
mmWave_dssAssertInfoMsg assertInfo
DSS assertion information.
#define SUBFRAME_USRR_NUM_CMPLX_ADC_SAMPLES
uint16_t numVirtualAntennas
number of virtual antennas
struct mmWave_OUT_MSG_header_t mmWave_OUT_MSG_header
The structure defines the message header for reporting detection information from data path....
uint8_t mboxProcToken
! chirpProc token
uint16_t chirpCount
chirp counter modulo number of chirps per frame
#define MMWAVE_MAX_FILE_NAME_SIZE
uint8_t subframeIndx
index of the subframe to which this object belongs
clusteringDBscanReport_t * dbScanState
Pointer to dBScan output Report array.
#define EDMA_INSTANCE_DSS
static void DSS_edmaBlockCopy(EDMA_Handle handle, uint32_t loadAddr, uint32_t runAddr, uint16_t size)
uint8_t parkingAssistNumBinsLog2
log2 of the number of bins for the parkingAssist module (used for scaling operations).
uint8_t parkingAssistNumBins
Number of bins for the parkingAssist module.
int32_t DSS_DataPathInit(void)
MmwDemo_timingInfo_t timingInfo
Timing information.
uint8_t dataPathDetectionPayload[DATAPATH_DET_PAYLOAD_SIZE]
struct mmWave_OUT_MSG_tl_t mmWave_OUT_MSG_tl
The structure defines the message body for reporting detected objects from data path....
ADCBuf_Handle adcBufHandle
mmWave control handle use to initialize the link infrastructure, which allows communication between t...
This is the data path processing header.
#define SUBFRAME_USRR_NUM_TX
void parkingAssistInit(DSS_DataPathObj *obj)
uint16_t parkingAssistMaxRange
maximum range to look for obstacles. .
uint16_t numRxAntennas
Number of receive channels.