This thread has been locked.

If you have a related question, please click the "Ask a related question" button in the top right corner. The newly created question will be automatically linked to this question.

TDA3XEVM: Sparse Optical Flow usecase not working as intended

Part Number: TDA3XEVM


Tool/software: PROCESSOR-SDK-VISION 03.08.00.00, CCS 12.5, USB560 JTAG Blackhawk Emulator, Leopard OV10640 CSI2 Cam, External Capture Card HDMI Display for visualization.

Hello,

I'm running the latest PSDK Version: 03.08.00.00, Release date: 25 Dec 2019 using a TDA3X Board and a OV10640 CSI2 Cam. I've previously ran ISS usecases and I took the code from VIP Single Cam Edgedetect usecase and successfully integrated and adapted it to fit the usecase 1CH ISS capture + iss isp + iss ldc+vtnf + display. I wanted to do the same for sparse optical flow, and I got the following result: Interestingly enough, EVE load is 0, even though the rectangles are being drawn and it's part of the EVE part of the Algorithm.

I get the square detection, but no green lines indicating from which direction the object is coming from as you can see from the userguide, this is what should be showing:

Here is the generated use case tree and my .c file which is based on the ISS use case, I integrated all the SOF functions from the VIP Single Cam Sparse optical flow. The code is from the 1CH ISS use case with the functions adapted and names changed to replace the ISS usecase in the start menu and not have to put my own anew. The autogenerated functions are also called, otherwise the usecase wouldn't be running in the first case. My suspicion is something going wrong in the Dup_capture link, as anything below that should be identical in my usecase the only thing changed is the capture input from VIP to ISS. I can't figure out why the lines aren't being drawn, it could also be the merge and sync algorithms...I've also disabled the SFM stuff, as it seems like it's only exclusive to VIP and I cannot use it, the SDK will not build properly as the input parameter expects a regular CaptureLink instead of ISS_Capture.

If anybody can run the VIP single cam SOF usecase just to check what the actual output is, I would also be very grateful to cross check what the expected output is instead of use the example TI provided in the picture.

#include "chains_edwinSOF_priv.h"
#include <src/include/chains_common.h>
#include <src/rtos/iss/include/iss_sensors.h>
#include <src/rtos/iss/include/iss_utils.h>
#include <src/rtos/iss/include/app_util_iss.h>
#include <src/include/chains_common_sfm.h>

#define CAPTURE_SENSOR_WIDTH      (1280)
#define CAPTURE_SENSOR_HEIGHT     (720)
#define SOF_NUM_OUT_BUF  (8)
#define SOF_ALG_WIDTH    (1280)
#define SOF_ALG_HEIGHT   (720)
//#define ENABLE_SFM_INPUT_TEST
#define ALG_AEWB_MEM_SIZE                           (896*1024)


Int32 Utils_fileWriteFile(char *fileName, Uint8 *addr, Uint32 size);

Int32 xUtils_fileExists( char *fileName )
{
    Int32 retVal = 0;
    Int32 hndlFile;

    hndlFile = File_open(fileName, "rb");

    if(hndlFile < 0)
    {
    retVal = 0;
    } else {
    retVal = 1;
    }
    File_close( hndlFile );

    return retVal;
}


Int32 xUtils_nextAvailableFile( char * buf, char * fmt, Int32 theIndex )
{
sprintf( buf, fmt, theIndex );

while( xUtils_fileExists( buf ) && theIndex < 9999 )
{
Vps_printf( "filename %s %d exists... skipping\n", buf, theIndex );
theIndex++;
    sprintf( buf, fmt, theIndex );
}

if( theIndex >= 9999 ) {
theIndex = 0;
    sprintf( buf, fmt, theIndex );
}
return theIndex;
}

Int32 lastExposureTime = 0;

Int32 xUtils_fileWriteInfo( char * filename, char * extra )
{
Int32 status = 0;
char buf [200];

sprintf( buf, "%s, %u, %s\n", filename, lastExposureTime, extra );

status = Utils_fileWriteFile( filename, (Uint8 *)buf, strlen( buf ));

return status;
}


typedef struct {

    chains_edwinSOFObj  ucObj;

    IssM2mSimcopLink_ConfigParams   simcopConfig;
    vpsissldcConfig_t               ldcCfg;
    vpsissvtnfConfig_t              vtnfCfg;

    UInt32                          captureOutWidth;
    UInt32                          captureOutHeight;
    UInt32                          displayWidth;
    UInt32                          displayHeight;

    Chains_Ctrl                    *chainsCfg;

    IssM2mSimcopLink_OperatingMode  simcopMode;
    Bool                            bypassVtnf;
    Bool                            bypassLdc;

    AppUtils_Obj             appSensInfo;
} chains_edwinSOF_DisplayAppObj;


char gChains_edwinSOF_runTimeMenu[] = {
"\r\n "
"\r\n ===================="
"\r\n Chains Run-time Menu"
"\r\n ===================="
"\r\n "
"\r\n 0: Stop Chain"
"\r\n "
"\r\n 1: Toggle VTNF ON/OFF"
"\r\n 2: Toggle LDC  ON/OFF"
"\r\n 3: Save Captured Frame"
"\r\n 4: Save SIMCOP Output Frame"
"\r\n 5: Save ISP Output Frame"
#ifdef ISS_ENABLE_DEBUG_TAPS
"\r\n 6: Enable Resizer Output"
"\r\n 7: Enable IPIPE Output"
"\r\n 8: Enable GLBCE Output"
"\r\n 9: Enable IPIPEIF Output"
"\r\n a: Enable Intermediate Output"
#endif
"\r\n "
"\r\n p: Print Performance Statistics "
"\r\n "
"\r\n Enter Choice: "
"\r\n "
};

Void chains_edwinSOF_SetMemAllocInfo(
                    chains_edwinSOF_DisplayAppObj *pObj)
{
    UInt32 align = SYSTEM_BUFFER_ALIGNMENT; /* 32 byte alignment*/
    IssCaptureLink_CreateParams             *pIssCapturePrm;
    IssM2mIspLink_CreateParams              *pIssM2mIspPrm;
    IssRszLink_CreateParams                 *pIssRszPrm;
    IssM2mSimcopLink_CreateParams           *pIssM2mSimcopPrm;
    AlgorithmLink_IssAewbCreateParams       *pAlg_IssAewbPrm;

    pIssCapturePrm    = &pObj->ucObj.IssCapturePrm;
    pIssM2mIspPrm     = &pObj->ucObj.IssM2mIspPrm;
    pIssRszPrm        = &pObj->ucObj.IssM2mResizerPrm;
    pIssM2mSimcopPrm  = &pObj->ucObj.IssM2mSimcopPrm;
    pAlg_IssAewbPrm   = &pObj->ucObj.Alg_IssAewbPrm;


    pIssCapturePrm->memAllocInfo.memSize =
          SystemUtils_align(pObj->captureOutWidth, align)
        * pObj->captureOutHeight
        * 2 /* 16-bit per pixel */
        * (pIssCapturePrm->outParams[0].numOutBuf+1)
            /* +1 for RAW data dump */
        ;

    pAlg_IssAewbPrm->memAllocInfo.memSize = ALG_AEWB_MEM_SIZE;

    pIssM2mIspPrm->memAllocInfo.memSize = 0;

    if(pIssM2mIspPrm->channelParams[0].enableOut[ISSM2MISP_LINK_OUTPUTQUE_IMAGE_RSZ_A])
    {
#ifdef ISS_ENABLE_DEBUG_TAPS
        /* RSZ A output */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              SystemUtils_align(pIssM2mIspPrm->channelParams[0].outParams.widthRszA,
                  ISSM2MISP_LINK_RSZ_BUF_ALIGN)
            * pIssM2mIspPrm->channelParams[0].outParams.heightRszA
            * 2 /* YUV420/422/RAW */
            * pIssM2mIspPrm->channelParams[0].numBuffersPerCh
            ;
#else
        /* RSZ A output */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              SystemUtils_align(pIssM2mIspPrm->channelParams[0].outParams.widthRszA,
                  ISSM2MISP_LINK_RSZ_BUF_ALIGN)
            * pIssM2mIspPrm->channelParams[0].outParams.heightRszA
            * 1.5 /* YUV420SP */
            * pIssM2mIspPrm->channelParams[0].numBuffersPerCh
            ;
#endif
    }

    if( pIssM2mIspPrm->channelParams[0].operatingMode
          == ISSM2MISP_LINK_OPMODE_2PASS_WDR
       )
    {
        /* Intermediate buffer in 2 pass WDR mode */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              SystemUtils_align(pObj->captureOutWidth, align)
            * pObj->captureOutHeight
            * 2 /* 16-bit per pixel */
            ;
    }

    if( pIssM2mIspPrm->channelParams[0].operatingMode
          == ISSM2MISP_LINK_OPMODE_2PASS_WDR_LINE_INTERLEAVED
       )
    {
        /* Intermediate buffer in 2 pass WDR mode */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              SystemUtils_align(pIssM2mIspPrm->channelParams[0].wdrOffsetPrms.width, align)
            * pIssM2mIspPrm->channelParams[0].wdrOffsetPrms.height
            * 2 /* 16-bit per pixel */
            ;
    }

    if (pIssM2mIspPrm->allocBufferForDump)
    {
        /* For Dumping Output frame */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              SystemUtils_align(pObj->captureOutWidth, align)
            * pObj->captureOutHeight
            * 2 /* 16-bit per pixel */
            ;
    }

    if(pIssM2mIspPrm->channelParams[0].enableOut[ISSM2MISP_LINK_OUTPUTQUE_IMAGE_RSZ_B])
    {
        /* RSZ B output */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              SystemUtils_align(pIssM2mIspPrm->channelParams[0].outParams.widthRszB,
                  ISSM2MISP_LINK_RSZ_BUF_ALIGN)
            * pIssM2mIspPrm->channelParams[0].outParams.heightRszB
            * 1.5 /* YUV420SP */
            * pIssM2mIspPrm->channelParams[0].numBuffersPerCh
            ;
    }

    if(pIssM2mIspPrm->channelParams[0].enableOut[ISSM2MISP_LINK_OUTPUTQUE_H3A])
    {
        /* H3A output */
        pIssM2mIspPrm->memAllocInfo.memSize +=
              ((pIssM2mIspPrm->channelParams[0].outParams.widthRszA/
                  pIssM2mIspPrm->channelParams[0].outParams.winWidthH3a)+1)
            * ((pIssM2mIspPrm->channelParams[0].outParams.heightRszA/
                  pIssM2mIspPrm->channelParams[0].outParams.winHeightH3a)+1)
            * ( sizeof(IssAwebH3aOutSumModeOverlay)
              + sizeof(IssAwebH3aOutUnsatBlkCntOverlay) )
            * pIssM2mIspPrm->channelParams[0].numBuffersPerCh
            ;
    }

/* To support WDR, two sets of statistics must be produced, one for short exposure and the other one for long exposure
    that's why there is a factor 2
    */
    if(pIssM2mIspPrm->channelParams[0].enableOut[ISSM2MISP_LINK_OUTPUTQUE_H3A_AF])
    {
        pIssM2mIspPrm->memAllocInfo.memSize +=  SystemUtils_align(2*pIssM2mIspPrm->channelParams[0].outParams.paxelNumHaf
            *pIssM2mIspPrm->channelParams[0].outParams.paxelNumVaf*sizeof(IssAfH3aOutOverlay), 128U) /* DSP cache requires 128 bytes alignment */
            *pIssM2mIspPrm->channelParams[0].numBuffersPerCh;
    }

    pIssRszPrm->memAllocInfo.memSize =
          SystemUtils_align(pIssRszPrm->channelParams[0].outParams.widthRszA,
              ISS_RSZ_LINK_RSZ_BUF_ALIGN)
        * pIssRszPrm->channelParams[0].outParams.heightRszA
        * 1.5 /* YUV420SP */
        * pIssRszPrm->channelParams[0].numBuffersPerCh
        ;

    pIssM2mSimcopPrm->memAllocInfo.memSize =
          SystemUtils_align(pIssM2mIspPrm->channelParams[0].outParams.widthRszA,
              ISS_RSZ_LINK_RSZ_BUF_ALIGN)
        * pIssM2mIspPrm->channelParams[0].outParams.heightRszA
        * 1.5
        * (pIssM2mSimcopPrm->channelParams[0].numBuffersPerCh+1)
           /* +1 for YUV data dump */
        ;

    pIssCapturePrm->memAllocInfo.memAddr =
        (UInt32)Utils_memAlloc(
                UTILS_HEAPID_DDR_CACHED_SR,
                pIssCapturePrm->memAllocInfo.memSize,
                align
            );
    UTILS_assert(pIssCapturePrm->memAllocInfo.memAddr!=NULL);

    pAlg_IssAewbPrm->memAllocInfo.memAddr =
        (UInt32)Utils_memAlloc(
                UTILS_HEAPID_DDR_CACHED_SR,
                pAlg_IssAewbPrm->memAllocInfo.memSize,
                align
            );
    UTILS_assert(pAlg_IssAewbPrm->memAllocInfo.memAddr!=NULL);

    pIssM2mIspPrm->memAllocInfo.memAddr =
        (UInt32)Utils_memAlloc(
                UTILS_HEAPID_DDR_CACHED_SR,
                pIssM2mIspPrm->memAllocInfo.memSize,
                align
            );
    UTILS_assert(pIssM2mIspPrm->memAllocInfo.memAddr!=NULL);

    pIssRszPrm->memAllocInfo.memAddr =
        (UInt32)Utils_memAlloc(
                UTILS_HEAPID_DDR_CACHED_SR,
                pIssRszPrm->memAllocInfo.memSize,
                align
            );
    UTILS_assert(pIssRszPrm->memAllocInfo.memAddr!=NULL);

    pIssM2mSimcopPrm->memAllocInfo.memAddr =
        (UInt32)Utils_memAlloc(
                UTILS_HEAPID_DDR_CACHED_SR,
                pIssM2mSimcopPrm->memAllocInfo.memSize,
                align
            );
    UTILS_assert(pIssM2mSimcopPrm->memAllocInfo.memAddr!=NULL);
}

/*
 * This function free's memory allocated by the use-case, if any
 */
Void chains_edwinSOF_FreeMemory(
                    chains_edwinSOF_DisplayAppObj *pObj)
{
    Int32 status;
    IssCaptureLink_CreateParams             *pIssCapturePrm;
    IssM2mIspLink_CreateParams              *pIssM2mIspPrm;
    IssRszLink_CreateParams                 *pIssRszPrm;
    IssM2mSimcopLink_CreateParams           *pIssM2mSimcopPrm;
    AlgorithmLink_IssAewbCreateParams       *pAlg_IssAewbPrm;

    pIssCapturePrm    = &pObj->ucObj.IssCapturePrm;
    pIssM2mIspPrm     = &pObj->ucObj.IssM2mIspPrm;
    pIssRszPrm        = &pObj->ucObj.IssM2mResizerPrm;
    pIssM2mSimcopPrm  = &pObj->ucObj.IssM2mSimcopPrm;
    pAlg_IssAewbPrm   = &pObj->ucObj.Alg_IssAewbPrm;

    if(pIssCapturePrm->memAllocInfo.memAddr)
    {
        status = Utils_memFree(
                    UTILS_HEAPID_DDR_CACHED_SR,
                    (Ptr)pIssCapturePrm->memAllocInfo.memAddr,
                    pIssCapturePrm->memAllocInfo.memSize
            );
        UTILS_assert(status==0);
    }

    if(pAlg_IssAewbPrm->memAllocInfo.memAddr)
    {
        status = Utils_memFree(
                    UTILS_HEAPID_DDR_CACHED_SR,
                    (Ptr)pAlg_IssAewbPrm->memAllocInfo.memAddr,
                    pAlg_IssAewbPrm->memAllocInfo.memSize
            );
        UTILS_assert(status==0);
    }

    if(pIssM2mIspPrm->memAllocInfo.memAddr)
    {
        status = Utils_memFree(
                    UTILS_HEAPID_DDR_CACHED_SR,
                    (Ptr)pIssM2mIspPrm->memAllocInfo.memAddr,
                    pIssM2mIspPrm->memAllocInfo.memSize
            );
        UTILS_assert(status==0);
    }

    if(pIssRszPrm->memAllocInfo.memAddr)
    {
        status = Utils_memFree(
                    UTILS_HEAPID_DDR_CACHED_SR,
                    (Ptr)pIssRszPrm->memAllocInfo.memAddr,
                    pIssRszPrm->memAllocInfo.memSize
            );
        UTILS_assert(status==0);
    }

    if(pIssM2mSimcopPrm->memAllocInfo.memAddr)
    {
        status = Utils_memFree(
                    UTILS_HEAPID_DDR_CACHED_SR,
                    (Ptr)pIssM2mSimcopPrm->memAllocInfo.memAddr,
                    pIssM2mSimcopPrm->memAllocInfo.memSize
            );
        UTILS_assert(status==0);
    }
}

/**
 *******************************************************************************
 *
 * \brief   Set VPE Create Parameters
 *
 *          This function is used to set the VPE params.
 *          It is called in Create function. It is advisable to have
 *          Chains_VipSingleCameraSparseOpticalFlow_ResetLinkPrms prior to set params
 *          so all the default params get set.
 *          Scaling parameters are set .
 *
 * \param   pPrm    [OUT]    VpeLink_CreateParams
 *
 *******************************************************************************
*/
Void chains_edwinSOF_SetVpePrm(
                    VpeLink_CreateParams *pPrm,
                    UInt32 outWidth,
                    UInt32 outHeight,
                    UInt32 srcWidth,
                    UInt32 srcHeight,
                    System_VideoDataFormat dataFormat
                    )
{
    pPrm->enableOut[0] = TRUE;

    pPrm->chParams[0].outParams[0].width = SystemUtils_floor(outWidth, 4);
    pPrm->chParams[0].outParams[0].height = SystemUtils_floor(outHeight, 2);
    pPrm->chParams[0].outParams[0].numBufsPerCh = 3;

    pPrm->chParams[0].scCropCfg.cropStartX = 0;
    pPrm->chParams[0].scCropCfg.cropStartY = 0;
    pPrm->chParams[0].scCropCfg.cropWidth  = srcWidth;
    pPrm->chParams[0].scCropCfg.cropHeight = srcHeight;

    pPrm->chParams[0].outParams[0].dataFormat = dataFormat;
    pPrm->chParams[0].outParams[0].numBufsPerCh = 2;
}

/**
 *******************************************************************************
 *
 * \brief   Set Algorithm related parameters
 *
 *******************************************************************************
*/
Void chains_edwinSOF_SetSparseOpticalFlowPrm(
                    AlgorithmLink_SparseOpticalFlowCreateParams *pAlgPrm,
                    AlgorithmLink_ObjectDrawCreateParams *pDrawPrm,
                    UInt32 startX,
                    UInt32 startY,
                    UInt32 width,
                    UInt32 height
                    )
{

    ChainsCommon_SetSOFConfig(pAlgPrm,
                              startX,
                              startY,
                              width,
                              height,
                              600);

    #ifndef ENABLE_SFM_INPUT_TEST
        pAlgPrm->enableRoi      = FALSE;
    #endif


    pDrawPrm->imgFrameStartX = startX;
    pDrawPrm->imgFrameStartY = startY;
    pDrawPrm->imgFrameWidth  = width;
    pDrawPrm->imgFrameHeight  = height;

    pDrawPrm->numOutBuffers = 5;
    pDrawPrm->sofMaxTrackPoints = pAlgPrm->maxNumKeyPoints;
    pDrawPrm->numDrawAlg = 1;
    pDrawPrm->drawAlgId[0] = ALGORITHM_LINK_OBJECT_DETECT_DRAW_ALG_SOF;

}

/**
 *******************************************************************************
 *
 * \brief   Set Sync Link Create Parameters
 *
 *          This function is used to set the sync params.
 *          It is called in Create function.
 *
 * \param   pPrm    [OUT]    SyncLink_CreateParams
 *
 *******************************************************************************
*/
Void chains_edwinSOF_SetSyncPrm(SyncLink_CreateParams *pPrm)

{
    pPrm->syncDelta = 1;
    pPrm->syncThreshold = 0xFFFF;
}





/**
 *******************************************************************************
 *
 * \brief   Set Display Create Parameters
 *
 *          This function is used to set the Display params.
 *          It is called in Create function. It is advisable to have
 *          chains_issIspSimcop_Display_ResetLinkPrms prior to set params
 *          so all the default params get set.
 *
 * \param   pPrm         [IN]    DisplayLink_CreateParams
 *
 *******************************************************************************
*/
Void chains_edwinSOF_SetDisplayPrms(
                                    DisplayLink_CreateParams *pPrm_Video,
                                    DisplayLink_CreateParams *pPrm_Grpx,
                                    DisplayLink_CreateParams *pPrm_VideoRszB,
                                    Chains_DisplayType displayType,
                                    UInt32 displayWidth,
                                    UInt32 displayHeight,
                                    UInt32 captureWidth,
                                    UInt32 captureHeight)
{
    UInt32 dispWidth, dispHeight;

    if(pPrm_Video)
    {
        if((displayType == CHAINS_DISPLAY_TYPE_SDTV_NTSC) ||
          (displayType == CHAINS_DISPLAY_TYPE_SDTV_PAL))
        {
            pPrm_Video->displayScanFormat = SYSTEM_SF_INTERLACED;
        }

        /* To maintain the aspect ratio, change the display tarWidth */
        dispWidth = captureWidth * displayHeight / captureHeight;
        dispHeight = displayHeight;

        if (dispWidth > displayWidth)
        {
            dispWidth = displayWidth;
            dispHeight = displayWidth * captureHeight / captureWidth;
        }


        pPrm_Video->rtParams.tarWidth  = dispWidth;
        pPrm_Video->rtParams.tarHeight = dispHeight;
        pPrm_Video->rtParams.posX      = (displayWidth - dispWidth) / 2U;
        pPrm_Video->rtParams.posY      = (displayHeight - dispHeight) / 2U;

        pPrm_Video->displayId          = DISPLAY_LINK_INST_DSS_VID1;
    }

    if(pPrm_VideoRszB)
    {
        if((displayType == CHAINS_DISPLAY_TYPE_SDTV_NTSC) ||
          (displayType == CHAINS_DISPLAY_TYPE_SDTV_PAL))
        {
            pPrm_VideoRszB->displayScanFormat = SYSTEM_SF_INTERLACED;
        }

        pPrm_VideoRszB->rtParams.tarWidth  = displayWidth/3;
        pPrm_VideoRszB->rtParams.tarHeight = displayHeight/3;
        pPrm_VideoRszB->rtParams.posX = displayWidth -
            pPrm_VideoRszB->rtParams.tarWidth - 10;
        pPrm_VideoRszB->rtParams.posY = displayHeight -
            pPrm_VideoRszB->rtParams.tarHeight - 10;
        pPrm_VideoRszB->displayId = DISPLAY_LINK_INST_DSS_VID2;
    }

    if(pPrm_Grpx)
    {
        if((displayType == CHAINS_DISPLAY_TYPE_SDTV_NTSC) ||
          (displayType == CHAINS_DISPLAY_TYPE_SDTV_PAL))
        {
            pPrm_Grpx->displayScanFormat = SYSTEM_SF_INTERLACED;
        }

        pPrm_Grpx->displayId = DISPLAY_LINK_INST_DSS_GFX1;
    }
}

Void chains_edwinSOF_SetSimcopConfig(
            chains_edwinSOF_DisplayAppObj *pObj)
{
    IssM2mSimcopLink_ConfigParams_Init(&pObj->simcopConfig);

    pObj->simcopConfig.ldcConfig = &pObj->ldcCfg;
    pObj->simcopConfig.vtnfConfig = &pObj->vtnfCfg;

    IssUtils_InitSimcopConfig(
        &pObj->simcopConfig, pObj->bypassLdc, pObj->bypassVtnf);

    IssUtils_SetimcopLdcVtnfRtConfig(
        &pObj->ldcCfg,
        &pObj->vtnfCfg,
        pObj->bypassLdc,
        pObj->bypassVtnf);

    /* MUST be called after link create and before link start */
    System_linkControl(
            pObj->ucObj.IssM2mSimcopLinkID,
            ISSM2MSIMCOP_LINK_CMD_SET_SIMCOPCONFIG,
            &pObj->simcopConfig,
            sizeof(pObj->simcopConfig),
            TRUE);
}

Void chains_edwinSOF_SetIspConfig(
            chains_edwinSOF_DisplayAppObj *pObj)
{
    appSetDefaultIspParams(&pObj->appSensInfo);
    appSetIspParamsFromDCC(&pObj->appSensInfo);
}

Void chains_edwinSOF_setMuxes(
            chains_edwinSOF_DisplayAppObj *pObj)
{
    /* Setup PinMux */
    ChainsPlatform_SetPinMux(pObj->chainsCfg->sensorName);

    /* Init Board Mux */
    ChainsBoard_SetBoardMux(pObj->chainsCfg->sensorName);
}

Void chains_edwinSOF_SetIssRszPrms(
        IssRszLink_CreateParams *issRszPrms,
        UInt32 outWidth,
        UInt32 outHeight)
{
    IssRszLink_ChannelParams *chPrms;

    chPrms = issRszPrms->channelParams;

    chPrms->enableOut[0U] = TRUE;
    chPrms->outParams.heightRszA = outHeight;
    chPrms->outParams.widthRszA = outWidth;
    chPrms->outParams.dataFormat = SYSTEM_DF_YUV420SP_UV;
}

/**
 *******************************************************************************
 *
 * \brief   Set link Parameters
 *
 *          It is called in Create function of the auto generated use-case file.
 *
 * \param pUcObj    [IN] Auto-generated usecase object
 * \param appObj    [IN] Application specific object
 *
 *******************************************************************************
*/

Void chains_edwinSOF_SetAppPrms(
    chains_edwinSOFObj *pUcObj, Void *appObj)
{
    chains_edwinSOF_DisplayAppObj *pObj
        = (chains_edwinSOF_DisplayAppObj*)appObj;

    UInt32 startX=0, startY=0;

    ChainsCommon_Sfm_Init(FALSE);

    #ifdef ENABLE_SFM_INPUT_TEST
    pObj->captureOutWidth  = 1920;
    pObj->captureOutHeight = 1080;
    #else
    pObj->captureOutWidth  = SOF_ALG_WIDTH;
    pObj->captureOutHeight = SOF_ALG_HEIGHT;
    #endif

    ChainsCommon_GetDisplayWidthHeight(
        pObj->chainsCfg->displayType,
        &pObj->displayWidth,
        &pObj->displayHeight
        );


    pObj->simcopMode = ISSM2MSIMCOP_LINK_OPMODE_LDC_VTNF;
    pObj->bypassVtnf = FALSE;
    pObj->bypassLdc  = FALSE;

    if ((pObj->chainsCfg->issLdcEnable == FALSE) &&
        (pObj->chainsCfg->issVtnfEnable == TRUE))
    {
        pObj->simcopMode = ISSM2MSIMCOP_LINK_OPMODE_VTNF;
        pObj->bypassVtnf = FALSE;
        pObj->bypassLdc  = TRUE;
    }
    else if ((pObj->chainsCfg->issLdcEnable == TRUE) &&
             (pObj->chainsCfg->issVtnfEnable == FALSE))
    {
        pObj->simcopMode = ISSM2MSIMCOP_LINK_OPMODE_LDC;
        pObj->bypassVtnf = TRUE;
        pObj->bypassLdc  = FALSE;
    }
    else if ((pObj->chainsCfg->issLdcEnable == FALSE) &&
             (pObj->chainsCfg->issVtnfEnable == FALSE))
    {
        pObj->simcopMode = ISSM2MSIMCOP_LINK_OPMODE_VTNF;
        pObj->bypassVtnf = TRUE;
        pObj->bypassLdc  = TRUE;
    }

    /* Initialize Simcop Pointers */
    pObj->simcopConfig.ldcConfig = &pObj->ldcCfg;
    pObj->simcopConfig.vtnfConfig = &pObj->vtnfCfg;

    /* Create the sensor now */
    strncpy(pObj->appSensInfo.sensorName, pObj->chainsCfg->sensorName,
        ISS_SENSORS_MAX_NAME);
    pObj->appSensInfo.numCh = 1;
    pObj->appSensInfo.ispOpMode = pObj->chainsCfg->ispOpMode;
    pObj->appSensInfo.simcopOpMode = pObj->simcopMode;
    pObj->appSensInfo.numCSI2Inst = 1;
    appCreateISSSensor(&pObj->appSensInfo);

    appInitIssCaptParams(&pObj->appSensInfo, pUcObj->IssCaptureLinkID,
        &pUcObj->IssCapturePrm);
    appInitIssIspParams(&pObj->appSensInfo, pUcObj->IssM2mIspLinkID,
        &pUcObj->IssM2mIspPrm);
    appInitIssSimcopParams(&pObj->appSensInfo, pUcObj->IssM2mSimcopLinkID,
        &pUcObj->IssM2mSimcopPrm);
    appInitIssAewbParams(&pObj->appSensInfo, pUcObj->Alg_IssAewbLinkID,
        &pUcObj->Alg_IssAewbPrm);

    /* Resizer B output will be shown as 1/3rd of display size */
    pUcObj->IssM2mIspPrm.channelParams[0u].outParams.widthRszB  =
        (pObj->displayWidth / 3) & (~0x1U);
    pUcObj->IssM2mIspPrm.channelParams[0u].outParams.heightRszB =
        (pObj->displayHeight / 3) & (~0x1U);

    /* Display requires around 4 buffers for 60fps chain, so increasing
       simcop output buffers to 4 */
    pUcObj->IssM2mSimcopPrm.channelParams[0u].numBuffersPerCh = 4;
    pUcObj->IssM2mResizerPrm.channelParams[0u].numBuffersPerCh = 4U;

    pUcObj->IssM2mIspPrm.allocBufferForDump = TRUE;
    pUcObj->IssCapturePrm.allocBufferForRawDump = TRUE;

    /*ChainsCommon_SingleCam_SetCapturePrms(&pUcObj->IssCapturePrm,
            CAPTURE_SENSOR_WIDTH,
            CAPTURE_SENSOR_HEIGHT,
            pObj->captureOutWidth,
            pObj->captureOutHeight,
            pObj->chainsCfg->captureSrc
            ); */

    //pUcObj->Dup_capturePrm.vipInst[0].numBufs = 7;

    /*#ifdef ENABLE_SFM_INPUT_TEST
    ChainsCommon_Sfm_SetCaptureCallback(&pUcObj->IssCapturePrm);
    startX = 320;
    startY = 180;
    #endif */

    chains_edwinSOF_SetSyncPrm(
                    &pUcObj->Sync_algPrm
                );

    chains_edwinSOF_SetSparseOpticalFlowPrm(
        &pUcObj->Alg_SparseOpticalFlowPrm,
        &pUcObj->Alg_ObjectDrawPrm,
        startX,
        startY,
        SOF_ALG_WIDTH,
        SOF_ALG_HEIGHT
        );


    ChainsCommon_SetGrpxSrcPrms(&pUcObj->GrpxSrcPrm,
                                pObj->displayWidth,
                                pObj->displayHeight);

    chains_edwinSOF_SetIssRszPrms(
        &pUcObj->IssM2mResizerPrm,
        ((pObj->displayWidth/3) & ~0x1), /* Even value needed */
        (pObj->displayHeight/3));

    pObj->captureOutWidth = pUcObj->IssCapturePrm.outParams[0U].width;
    pObj->captureOutHeight = pUcObj->IssCapturePrm.outParams[0U].height;


    /*
     * call this function to allocate memory from use-case
     * if this function is not called memory is allocated
     * from within the respective link
     */
    chains_edwinSOF_SetMemAllocInfo(pObj);

    chains_edwinSOF_SetDisplayPrms(
        &pUcObj->Display_algPrm,
            &pUcObj->Display_GrpxPrm,
            &pUcObj->Display_VideoRszBPrm,
            pObj->chainsCfg->displayType,
            pObj->displayWidth,
            pObj->displayHeight,
            pUcObj->IssM2mIspPrm.channelParams[0U].outParams.widthRszA,
            pUcObj->IssM2mIspPrm.channelParams[0U].outParams.heightRszA);

    ChainsCommon_StartDisplayCtrl(
        pObj->chainsCfg->displayType,
        pObj->displayWidth,
        pObj->displayHeight);
}

/**
 *******************************************************************************
 *
 * \brief   Start the capture display Links
 *
 *          Function sends a control command to capture and display link to
 *          to Start all the required links . Links are started in reverce
 *          order as information of next link is required to connect.
 *          System_linkStart is called with LinkId to start the links.
 *
 * \param   pObj  [IN] chains_edwinSOF_DisplayAppObj
 *
 * \return  SYSTEM_LINK_STATUS_SOK on success
 *
 *******************************************************************************
*/
Void chains_edwinSOF_StartApp(chains_edwinSOF_DisplayAppObj *pObj)
{
    Chains_memPrintHeapStatus();

    /* Sets the Simcop Config also */
    chains_edwinSOF_SetIspConfig(pObj);
    chains_edwinSOF_SetSimcopConfig(pObj);

    chains_edwinSOF_setMuxes(pObj);

    appStartIssSensorSerDes(&pObj->appSensInfo);

    ChainsCommon_StartDisplayDevice(pObj->chainsCfg->displayType);


    /* ChainsCommon_StartCaptureDevice(
    pObj->chainsCfg->captureSrc,
    pObj->captureOutWidth,
    pObj->captureOutHeight
    ); */


    chains_edwinSOF_Start(&pObj->ucObj);

    Chains_prfLoadCalcEnable(TRUE, FALSE, FALSE);
}

/**
 *******************************************************************************
 *
 * \brief   Delete the capture display Links
 *
 *          Function sends a control command to capture and display link to
 *          to delete all the prior created links
 *          System_linkDelete is called with LinkId to delete the links.
 *
 * \param   pObj   [IN]   chains_edwinSOF_DisplayAppObj
 *
 *******************************************************************************
*/
Void chains_edwinSOF_StopAndDeleteApp(chains_edwinSOF_DisplayAppObj *pObj)
{
    chains_edwinSOF_Stop(&pObj->ucObj);
    chains_edwinSOF_Delete(&pObj->ucObj);

    chains_edwinSOF_FreeMemory(pObj);

    ChainsCommon_StopDisplayCtrl();

    appStopISSSensor(&pObj->appSensInfo);

    appDeleteISSSensor(&pObj->appSensInfo);


    ChainsCommon_StopCaptureDevice(pObj->chainsCfg->captureSrc);


    ChainsCommon_StopDisplayDevice(pObj->chainsCfg->displayType);


    ChainsCommon_Sfm_DeInit();

    /* Print the HWI, SWI and all tasks load */
    /* Reset the accumulated timer ticks */
    Chains_prfLoadCalcEnable(FALSE, TRUE, TRUE);
}

/**
 *******************************************************************************
 *
 * \brief   Single Channel Capture Display usecase function
 *
 *          This functions executes the create, start functions
 *
 *          Further in a while loop displays run time menu and waits
 *          for user inputs to print the statistics or to end the demo.
 *
 *          Once the user inputs end of demo stop and delete
 *          functions are executed.
 *
 * \param   chainsCfg       [IN]   Chains_Ctrl
 *
 *******************************************************************************
*/
Void Chains_edwinSOF_Display(Chains_Ctrl *chainsCfg)
{
    char ch;
    UInt32 done = FALSE;
    chains_edwinSOF_DisplayAppObj chainsObj;
    IssM2mIspLink_IspOutputTapParams ispTapPrms;
    Int32 CapImCounter = 0;
    char fName[128];
    Int32 status = 0;
    IssCaptureLink_GetSaveFrameStatus rawSaveFrameStatus;
    IssM2mSimcopLink_GetSaveFrameStatus simcopSaveFrameStatus;
    IssM2mIspLink_GetSaveFrameStatus ispSaveFrameStatus;
    UInt32 chId = 0U;

    chainsObj.bypassVtnf = 0; /* KW error fix */
    chainsObj.bypassLdc  = 0; /* KW error fix */

    #ifdef ENABLE_SFM_INPUT_TEST
    if(chainsObj.chainsCfg->captureSrc!=CHAINS_CAPTURE_SRC_HDMI_1080P)
    {
        Vps_printf(" ### ONLY HDMI 1080p60 input supported for this usecase ");
        Vps_printf(" ### Please choose HDMI 1080p60 Capture Source using option 's'\n");
        return;
    }
    #endif

    Vps_printf(" Entered Chains_edwinSOF_Display \n");

    if (TRUE == IssM2mIspLink_IsWdrMode(chainsCfg->ispOpMode))
    {
        Vps_printf(" CHAINS: Please make sure BSP is build with WDR and LDC enabled !!!\n");
    }

    chainsObj.chainsCfg = chainsCfg;


    /* Initialize Video Sensor, so that Algorithm can use Params
       from Vid Sensor layer */
    chains_edwinSOF_Create(&chainsObj.ucObj, &chainsObj);
    ChainsCommon_SetIssCaptureErrorHandlingCb(chainsObj.ucObj.IssCaptureLinkID);
    chains_edwinSOF_StartApp(&chainsObj);

    while(!done)
    {
        Vps_printf(gChains_edwinSOF_runTimeMenu);

        ch = Chains_readChar();

        switch(ch)
        {
            case '0':
                done = TRUE;
                break;
            case '1':
                /* toogle VTNF ON/OFF */
                chainsObj.bypassVtnf ^= 1;
                chains_edwinSOF_SetSimcopConfig(&chainsObj);
                if(chainsObj.bypassVtnf)
                {
                    Vps_printf(" CHAINS: VTNF is BYPASSED !!!\n");
                }
                else
                {
                    Vps_printf(" CHAINS: VTNF is ENABLED !!!\n");
                }
                break;
            case '2':
                /* toogle LDC ON/OFF */
                chainsObj.bypassLdc ^= 1;
                chains_edwinSOF_SetSimcopConfig(&chainsObj);
                if(chainsObj.bypassLdc)
                {
                    Vps_printf(" CHAINS: LDC is BYPASSED !!!\n");
                }
                else
                {
                    Vps_printf(" CHAINS: LDC is ENABLED !!!\n");
                }
                break;

            case '3':
                {
                /* Send command to Capture Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssCaptureLinkID,
                        ISSCAPTURE_LINK_CMD_SAVE_FRAME,
                        &chId,
                        sizeof(chId),
                        TRUE);

                        do {
                              System_linkControl(
                              chainsObj.ucObj.IssCaptureLinkID,
                              ISSCAPTURE_LINK_CMD_GET_SAVE_FRAME_STATUS,
                              &rawSaveFrameStatus,
                              sizeof(IssCaptureLink_GetSaveFrameStatus),
                              TRUE);

                        } while (rawSaveFrameStatus.isSaveFrameComplete == FALSE);
                        CapImCounter = xUtils_nextAvailableFile( fName, "raw%04u.raw", CapImCounter );

                        status = Utils_fileWriteFile( fName, (UInt8*)rawSaveFrameStatus.bufAddr, rawSaveFrameStatus.bufSize);

                        sprintf( fName, "raw%04u.txt", CapImCounter );

                        if(status)
                        {
                            Vps_printf("Error %d: Error performing file write\n",status);
                            xUtils_fileWriteInfo( fName, "RAW, Error" );
                        } else {
                            Vps_printf("Wrote image %s to file\n",fName);
                            xUtils_fileWriteInfo( fName, "RAW, OK" );
                    }

                break;
                }
            case '4':
                /* Send command to Capture Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mSimcopLinkID,
                        ISSM2MSIMCOP_LINK_CMD_SAVE_FRAME,
                        &chId,
                        sizeof(chId),
                        TRUE);
                        simcopSaveFrameStatus.chId = 0;
                        do {
                              System_linkControl(
                              chainsObj.ucObj.IssM2mSimcopLinkID,
                              ISSM2MSIMCOP_LINK_CMD_GET_SAVE_FRAME_STATUS,
                              &simcopSaveFrameStatus,
                              sizeof(IssM2mSimcopLink_GetSaveFrameStatus),
                              TRUE);

                        } while (simcopSaveFrameStatus.isSaveFrameComplete == FALSE);
                        CapImCounter = xUtils_nextAvailableFile( fName, "SIMCOP%04u.yuv", CapImCounter );

                        status = Utils_fileWriteFile( fName, (UInt8*)simcopSaveFrameStatus.bufAddr, simcopSaveFrameStatus.bufSize);

                        sprintf( fName, "SIMCOP%04u.txt", CapImCounter );

                        if(status)
                        {
                            Vps_printf("Error %d: Error performing file write\n",status);
                            xUtils_fileWriteInfo( fName, "NV12, Error" );
                        } else {
                            Vps_printf("Wrote image %s to file\n",fName);
                            xUtils_fileWriteInfo( fName, "NV12, OK" );
                    }

                break;
            case '5':
                /* Send command to ISP Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mIspLinkID,
                        ISSM2MISP_LINK_CMD_SAVE_FRAME,
                        &chId,
                        sizeof(chId),
                        TRUE);
                        ispSaveFrameStatus.chId = 0;

                        do {
                              System_linkControl(
                              chainsObj.ucObj.IssM2mIspLinkID,
                              ISSM2MISP_LINK_CMD_GET_SAVE_FRAME_STATUS,
                              &ispSaveFrameStatus,
                              sizeof(IssCaptureLink_GetSaveFrameStatus),
                              TRUE);

                        } while (ispSaveFrameStatus.isSaveFrameComplete == FALSE);
                        CapImCounter = xUtils_nextAvailableFile( fName, "ISP%04u.yuv", CapImCounter );

                        status = Utils_fileWriteFile( fName, (UInt8*)ispSaveFrameStatus.bufAddr, ispSaveFrameStatus.bufSize);

                        sprintf( fName, "ISP%04u.txt", CapImCounter );

                        if(status)
                        {
                            Vps_printf("Error %d: Error performing file write\n",status);
                            xUtils_fileWriteInfo( fName, "NV12, Error" );
                        } else {
                            Vps_printf("Wrote image %s to file\n",fName);
                            xUtils_fileWriteInfo( fName, "NV12, OK" );
                    }

                break;
            case '6':
                ispTapPrms.chId = 0U;
                ispTapPrms.outputTapModule = ISSM2MISP_LINK_ISP_TAP_RESIZER_OUTPUT;
                /* Send command to ISP Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mIspLinkID,
                        ISSM2MISP_LINK_CMD_SET_TAP_PARAMS,
                        &ispTapPrms,
                        sizeof(ispTapPrms),
                        TRUE);
                break;
            case '7':
                ispTapPrms.chId = 0U;
                ispTapPrms.outputTapModule = ISSM2MISP_LINK_ISP_TAP_IPIPE_OUTPUT;
                /* Send command to ISP Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mIspLinkID,
                        ISSM2MISP_LINK_CMD_SET_TAP_PARAMS,
                        &ispTapPrms,
                        sizeof(ispTapPrms),
                        TRUE);
                break;
            case '8':
                ispTapPrms.chId = 0U;
                ispTapPrms.outputTapModule = ISSM2MISP_LINK_ISP_TAP_GLBCE_OUTPUT;
                /* Send command to ISP Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mIspLinkID,
                        ISSM2MISP_LINK_CMD_SET_TAP_PARAMS,
                        &ispTapPrms,
                        sizeof(ispTapPrms),
                        TRUE);
                break;
            case '9':
                ispTapPrms.chId = 0U;
                ispTapPrms.outputTapModule = ISSM2MISP_LINK_ISP_TAP_IPIPEIF_OUTPUT;
                /* Send command to ISP Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mIspLinkID,
                        ISSM2MISP_LINK_CMD_SET_TAP_PARAMS,
                        &ispTapPrms,
                        sizeof(ispTapPrms),
                        TRUE);
                break;
            case 'a':
                ispTapPrms.chId = 0U;
                ispTapPrms.outputTapModule = ISSM2MISP_LINK_ISP_TAP_INTERMED_OUTPUT;
                /* Send command to ISP Link to save a frame */
                System_linkControl(
                        chainsObj.ucObj.IssM2mIspLinkID,
                        ISSM2MISP_LINK_CMD_SET_TAP_PARAMS,
                        &ispTapPrms,
                        sizeof(ispTapPrms),
                        TRUE);
                break;
            case 'p':
            case 'P':
                ChainsCommon_PrintStatistics();
                chains_edwinSOF_printStatistics(&chainsObj.ucObj);
                break;
            default:
                Vps_printf("\nUnsupported option '%c'. Please try again\n", ch);
                break;
        }
    }

    chains_edwinSOF_StopAndDeleteApp(&chainsObj);

}


I've also breakpointed my way through the draw library and saw how the 'drawlines and squares' functions were being triggered, so I was jumping into those, but I have the suspicion that the values are not properly passed during either dup_capture, sync or merge most likely. I also used the expressions tab during the draw process and saw how the X and Y coordinates are subtracted during the lines and they give 0, so it always subtracted the same value from itself, with the lines being 0.

  • UPDATE: I got it working, linePrm.lineSize = 2; needs to be used, originally  linePrm.lineSize = 1; was used, for some reason this doesn't work even though its the default configuration.

    Void AlgorithmLink_objectDrawSofFlows(AlgorithmLink_ObjectDrawObj *pObj)
    {
        sofctr++;
        Draw2D_LinePrm rectLinePrm, linePrm;
        strackInfo * trackInfo;
    
        UInt16 vx, vy, xmin, xmax, ymin, ymax;
        UInt16 numLines, i, j, minPt, maxPt, idx, startX, startY;
    
        if(pObj->pSofOutput==NULL)
            return;
    
        trackInfo = pObj->pSofOutput;
    
        startX  = startY = SOF_ALGLINK_PAD_PIXELS;
    
        rectLinePrm.lineSize = 2;
        rectLinePrm.lineColor = COLOR_RED;
        rectLinePrm.lineColorFormat = SYSTEM_DF_YUV420SP_UV;
    
        linePrm.lineSize = 2;
        linePrm.lineColor = COLOR_GREEN;
        linePrm.lineColorFormat = SYSTEM_DF_YUV420SP_UV;