dwSensorManager_start fail in driveworks 6.0.10

Please provide the following info (tick the boxes after creating this topic):
Software Version
[*] DRIVE OS 6.0.10.0
DRIVE OS 6.0.8.1
DRIVE OS 6.0.6
DRIVE OS 6.0.5
DRIVE OS 6.0.4 (rev. 1)
DRIVE OS 6.0.4 SDK
other

Target Operating System
Linux
QNX
other

Hardware Platform
[*] DRIVE AGX Orin Developer Kit (940-63710-0010-300)
DRIVE AGX Orin Developer Kit (940-63710-0010-200)
DRIVE AGX Orin Developer Kit (940-63710-0010-100)
DRIVE AGX Orin Developer Kit (940-63710-0010-D00)
DRIVE AGX Orin Developer Kit (940-63710-0010-C00)
DRIVE AGX Orin Developer Kit (not sure its number)
other

SDK Manager Version
2.1.0
other

Host Machine Version
native Ubuntu Linux 20.04 Host installed with SDK Manager
native Ubuntu Linux 20.04 Host installed with DRIVE OS Docker Containers
native Ubuntu Linux 18.04 Host installed with DRIVE OS Docker Containers
other

Issue Description
<Please provide details about your query/application pipeline/usecase/pictures here >

Error String
< Please provide just the error messages here >

Logs
Provide logs in text box instead of image

Please paste the complete application log here. If there are multiple logs, please use multiple text box

In the drive os 6.0.9 version, we tried to integrate the DriveWorks library into ROS2 and compile the code directly on the Orin. In the 5.16 version of DriveWorks, we could obtain camera data through DriveWorks and transmit the data through a ROS2 topic. However, when we upgraded the Drive OS on the Orin to 6.0.10 and updated the DriveWorks in our code to version 5.20, we encountered an error where the dwSensorManager_start function failed to run. After updating the Drive OS on the Orin to 6.0.10, we have updated the corresponding camera driver and tested the rig file using the sample_camera, which can obtain data normally. We have also tested that using the same function in our code to obtain camera data as in sample_camera is normal. However, there is a problem with using SensorManager. We do not have an NVOnline license, so please help us take a look.

 this->declare_parameter<std::string>("rig", "");

    RCLCPP_INFO(this->get_logger(), this->get_parameter("rig").as_string().data());

    dwContextParameters sdkParams = {};
    dwStatus status;
    status = dwInitialize(&m_context, DW_VERSION, &sdkParams);
    if (status != DW_SUCCESS)
    {
        RCLCPP_ERROR(this->get_logger(), "Failed to init Driveworks SDK. Error: %s", dwGetStatusName(status));
        return;
    }

    status = dwSAL_initialize(&m_sal, m_context);
    if (status != DW_SUCCESS)
    {
        RCLCPP_ERROR(this->get_logger(), "Failed to create HAL module of Driveworks SDK. Error: %s", dwGetStatusName(status));
        return;
    }

    dwRigHandle_t rig_config{};
    dwRig_initializeFromFile(&rig_config, m_context, this->get_parameter("rig").as_string().data());

    uint32_t cnt = 0;
    CHECK_DW_ERROR(dwRig_getSensorCountOfType(&cnt, DW_SENSOR_CAMERA, rig_config));

    dwSensorManagerParams smParams{};

    for (uint32_t i = 0; i < cnt; i++)
    {
        uint32_t camera_sensor_idx = 0;
        CHECK_DW_ERROR(dwRig_findSensorByTypeIndex(&camera_sensor_idx, DW_SENSOR_CAMERA, i, rig_config));

        smParams.enableSensors[i] = camera_sensor_idx;
        smParams.numEnableSensors++;

        const char *camera_name;

        CHECK_DW_ERROR(dwRig_getSensorName(&camera_name, camera_sensor_idx, rig_config));

        m_idx_name_map[camera_sensor_idx] = {std::string(camera_name), i};
    }

    CHECK_DW_ERROR(dwSensorManager_initializeFromRigWithParams(&m_sensor_manager, rig_config, &smParams, 1024, m_sal));

    for (const auto &pair : m_idx_name_map)
    {
        uint32_t camera_sensor_idx = pair.first;

        dwSensorHandle_t camera_sensor = DW_NULL_HANDLE;
        CHECK_DW_ERROR(dwSensorManager_getSensorHandle(&camera_sensor, camera_sensor_idx, m_sensor_manager));

        dwImageProperties image_properties{};
        CHECK_DW_ERROR(dwSensorCamera_getImageProperties(&image_properties, DW_CAMERA_OUTPUT_CUDA_RGBA_UINT8, camera_sensor));

        image_properties.format = DW_IMAGE_FORMAT_RGB_UINT8;

        uint32_t camera_sensor_id = pair.second.second;

        CHECK_DW_ERROR(dwImage_create(&m_cuda_rgb_frame[camera_sensor_id], image_properties, m_context));

        CHECK_DW_ERROR(dwImageStreamer_initialize(&m_streamer_cuda_to_cpu[camera_sensor_id], &image_properties, DW_IMAGE_CPU, m_context));

        m_publisher[camera_sensor_id] = this->create_publisher<sensor_msgs::msg::Image>(pair.second.first, 10);
    }

    CHECK_DW_ERROR(dwSensorManager_start(m_sensor_manager));
zhangzs@tegra-ubuntu:~/adas_ws$ ros2 launch camera multiple_camera_publisher_launch.py
[INFO] [launch]: All log files can be found below /home/zhangzs/.ros/log/2024-10-28-14-05-00-378753-tegra-ubuntu-16236
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [multiple_camera_publisher-1]: process started with pid [16241]
[multiple_camera_publisher-1] [INFO] [1730095500.673194880] [multiple_camera_publisher]: src/camera/config/rig.json
[multiple_camera_publisher-1] terminate called after throwing an instance of 'std::runtime_error'
[multiple_camera_publisher-1]   what():  [2024-10-28 14:05:02] DW Error DW_INTERNAL_ERROR executing DW function:
[multiple_camera_publisher-1]  dwSensorManager_start(m_sensor_manager)
[multiple_camera_publisher-1]  at /home/zhangzs/adas_ws/src/camera/src/multiple_camera_publisher.cpp:74
[ERROR] [multiple_camera_publisher-1]: process has died [pid 16241, exit code -6, cmd '/home/zhangzs/adas_ws/install/camera/lib/camera/multiple_camera_publisher --ros-args -r __node:=multiple_camera_publisher --params-file /tmp/launch_params_w6qp8c1a'].

I used driveos 6.0.10 docker and added an example to the dirveworks sample, and the same error was reported in this example. So I suspect it’s driveworks.

The associated code and rig files are as follows:

/////////////////////////////////////////////////////////////////////////////////////////
//
// Notice
// ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
// NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
// THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
// MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
//
// NVIDIA CORPORATION & AFFILIATES assumes no responsibility for the consequences of use of such
// information or for any infringement of patents or other rights of third parties that may
// result from its use. No license is granted by implication or otherwise under any patent
// or patent rights of NVIDIA CORPORATION & AFFILIATES. No third party distribution is allowed unless
// expressly authorized by NVIDIA. Details are subject to change without notice.
// This code supersedes and replaces all information previously supplied.
// NVIDIA CORPORATION & AFFILIATES products are not authorized for use as critical
// components in life support devices or systems without express written approval of
// NVIDIA CORPORATION & AFFILIATES.
//
// SPDX-FileCopyrightText: Copyright (c) 2019-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
// SPDX-License-Identifier: LicenseRef-NvidiaProprietary
//
// NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
// property and proprietary rights in and to this material, related
// documentation and any modifications thereto. Any use, reproduction,
// disclosure or distribution of this material and related documentation
// without an express license agreement from NVIDIA CORPORATION or
// its affiliates is strictly prohibited.
//
/////////////////////////////////////////////////////////////////////////////////////////
#include <framework/Checks.hpp>
#include <dw/core/base/Version.h>
#include <dw/interop/streamer/ImageStreamer.h>
#include <dw/rig/Rig.h>
#include <dw/sensors/camera/Camera.h>
#include <dw/sensors/camera/CodecHeaderVideo.h>
#include <dw/sensors/codecs/Codec.h>
#include <dw/sensors/codecs/sensorserializer/SensorSerializer.h>

// SDK
#include <dw/core/base/Version.h>
#include <dw/calibration/engine/Engine.h>
#include <dw/sensors/sensormanager/SensorManager.h>

#include <limits>
#include <iostream>

// #######################################################################################
int main(int argc, const char **argv)
{
    dwContextHandle_t context = DW_NULL_HANDLE;
    dwContextParameters sdkParams = {};
    (dwInitialize(&context, DW_VERSION, &sdkParams));

    dwSALHandle_t sal = DW_NULL_HANDLE;
    (dwSAL_initialize(&sal, context));

    // the complete configuration is automatically loaded by dwRig module
    dwRigHandle_t m_rigConfig{};
    (dwRig_initializeFromFile(&m_rigConfig, context, "/home/zhangzs/adas_ws/src/camera/config/rig.json"));

    uint32_t m_cameraLeftSensorIdx = std::numeric_limits<decltype(m_cameraLeftSensorIdx)>::max();
    (dwRig_findSensorByName(&m_cameraLeftSensorIdx, "camera_sample0", m_rigConfig));

    uint32_t m_cameraRightSensorIdx = std::numeric_limits<decltype(m_cameraRightSensorIdx)>::max();
    (dwRig_findSensorByName(&m_cameraRightSensorIdx, "camera_sample1", m_rigConfig));

    dwSensorManagerHandle_t m_sensorManager = DW_NULL_HANDLE;

    dwSensorManagerParams smParams{};

    smParams.enableSensors[0] = m_cameraLeftSensorIdx;
    smParams.numEnableSensors++;

    smParams.enableSensors[1] = m_cameraRightSensorIdx;
    smParams.numEnableSensors++;

    // initialize Driveworks SensorManager directly from rig file
    (dwSensorManager_initializeFromRigWithParams(&m_sensorManager, m_rigConfig, &smParams, 1024, sal));

    CHECK_DW_ERROR(dwSensorManager_start(m_sensorManager));

    while (true)
    {
        std::cout << "in" << "\n";

        const dwSensorEvent *event = nullptr;
        dwImageHandle_t m_pendingFrame, m_pendingFrameLeft, m_pendingFrameRight;
        m_pendingFrame = m_pendingFrameLeft = m_pendingFrameRight = nullptr;

        bool get_data = false;

        while (!get_data)
        {
            dwCameraFrameHandle_t frames[2] = {DW_NULL_HANDLE, DW_NULL_HANDLE};
            dwStatus res = dwSensorManager_acquireNextEvent(&event, 3000000, m_sensorManager);
            if (res == DW_SUCCESS)
            {
                switch (event->type)
                {
                case DW_SENSOR_CAMERA:
                    // Pass frames in left-right order
                    for (uint32_t i = 0; i < event->numCamFrames; ++i)
                    {
                        uint32_t idx = event->sensorIndices[i];
                        if (idx == m_cameraLeftSensorIdx)
                            frames[0] = event->camFrames[i];
                        else if (idx == m_cameraRightSensorIdx)
                            frames[1] = event->camFrames[i];
                    }

                    // handleCameras(frames);
                    dwImageHandle_t img_left;
                    (dwSensorCamera_getImage(&img_left, DW_CAMERA_OUTPUT_NATIVE_PROCESSED, frames[0]));

                    dwTime_t timestamp_left;
                    dwImage_getTimestamp(&timestamp_left, img_left);

                    (dwSensorCamera_returnFrame(&frames[0]));

                    dwImageHandle_t img_rigth;
                    (dwSensorCamera_getImage(&img_rigth, DW_CAMERA_OUTPUT_NATIVE_PROCESSED, frames[1]));

                    dwTime_t timestamp_rigth;
                    dwImage_getTimestamp(&timestamp_rigth, img_rigth);

                    (dwSensorCamera_returnFrame(&frames[1]));

                    // std::cout << timestamp_left - timestamp_rigth << "lll" << "\n";
                    std::cout << "1" << "\n";

                    get_data = true;

                    break;
                case DW_SENSOR_IMU:
                case DW_SENSOR_CAN:
                case DW_SENSOR_GPS:
                case DW_SENSOR_RADAR:
                case DW_SENSOR_TIME:
                case DW_SENSOR_LIDAR:
                case DW_SENSOR_DATA:
                case DW_SENSOR_COUNT:
                default:
                    break;
                }
            }
            else
            {
                get_data = true;
                std::cout << "0"<<res<<std::endl;
            }
        }

        if (event != nullptr)
        {
            (dwSensorManager_releaseAcquiredEvent(event, m_sensorManager));
            std::cout << "2" << "\n";
        }
    }

    return 1;
}
{
    "rig": {
        "sensors": [
            {
                "name": "camera_sample0",
                "nominalSensor2Rig_FLU": {
                    "roll-pitch-yaw": [
                        0.0,
                        0.0,
                        0.0
                    ],
                    "t": [
                        1.8621,
                        -0.1939,
                        1.3165
                    ]
                },
                "parameter": "camera-name=OX08D10-EXAE-AA1C_R1D,interface=csi-ab,CPHY-mode=1,link=0,output-format=processed,async-record=1,file-buffer-size=16777216,skip-eeprom=1,nito-file=/usr/share/camera/OX08D10-EXAE-AA1C_R1D.nito",
                "properties": {
                    "Model": "ftheta",
                    "bw-poly": "0.000000000000000 5.35356812179089e-4 4.99266072928606e-10 4.27370422037554e-12 -6.68245573791717e-16",
                    "distortion": "10.0 10.0 10.0",
                    "cx": "1927.764404",
                    "cy": "1096.686646",
                    "height": "2160",
                    "width": "3840"
                },
                "protocol": "camera.gmsl"
            },
            {
                "name": "camera_sample1",
                "nominalSensor2Rig_FLU": {
                    "roll-pitch-yaw": [
                        0.0,
                        0.0,
                        0.0
                    ],
                    "t": [
                        1.8621,
                        -0.1939,
                        1.3165
                    ]
                },
                "parameter": "camera-name=OX08D10-EXAE-AA1C_R1D,interface=csi-ab,CPHY-mode=1,link=1,output-format=processed,async-record=1,file-buffer-size=16777216,skip-eeprom=1,nito-file=/usr/share/camera/OX08D10-EXAE-AA1C_R1D.nito",
                "properties": {
                    "Model": "ftheta",
                    "bw-poly": "0.000000000000000 5.35356812179089e-4 4.99266072928606e-10 4.27370422037554e-12 -6.68245573791717e-16",
                    "distortion": "10.0 10.0 10.0",
                    "cx": "1927.764404",
                    "cy": "1096.686646",
                    "height": "2160",
                    "width": "3840"
                },
                "protocol": "camera.gmsl"
            },
            {
                "name": "time:nvpps:rec:00",
                "nominalSensor2Rig_FLU": {
                    "roll-pitch-yaw": [
                        0,
                        0,
                        0
                    ],
                    "t": [
                        0,
                        0,
                        0
                    ]
                },
                "parameter": "reference-type=NONE,nvpps-device=/dev/nvpps0",
                "properties": null,
                "protocol": "time.nvpps"
            }
        ],
        "vehicle": {
            "valid": false
        }
    },
    "version": 2
}

zhangzs@tegra-ubuntu:~/nvidia$ ./sample_camera2
MAX96712: Revision 5 detected
MAX96712 Link 0: PHY optimization was enabled
MAX96712 Link 1: PHY optimization was enabled
MAX96717: Revision 4 detected!
OX08D10_R1D Driver Version:  1.0.1.0 build(Oct 23 2024 16:06:17)
OX08D10: Revision R1D detected!
OX08D10: [ 21 08 0D 01 00 ] :: [ 07,C5,05 ]
OX08D10 Get Sensitivity Ratio: FFFF 389D 02D9 389D
MAX96717: Revision 4 detected!
OX08D10_R1D Driver Version:  1.0.1.0 build(Oct 23 2024 16:06:17)
OX08D10: Revision R1D detected!
OX08D10: [ 21 08 0D 01 00 ] :: [ 07,C5,05 ]
OX08D10 Get Sensitivity Ratio: FFFF 3897 02DA 3897
OX08D10: OX08D10SetDeviceConfig - 30FPS
;[TpgEnabled] 0
;[charModeEnabled] 0
;[charModeExpNo  ] 0
;[ numFrameReportBytes ] 0
;[ nnumActiveExposures ] 4
;[ frameTiming - tclk ] 102083333
;[ frameTiming - hts ] 2476
;[ frameTiming - vts ] 1374
;[ frameTiming - hsize ] 3840
;[ frameTiming - vsize ] 2160
;[ frameTiming - binning ] 0
;[ frameTiming - timeLine ] 2.425470e-05
;[ frameTiming - fps ] 30.0066
;[ mfCfg - Mirror Enable ] 0
;[ mfCfg - Flip Enable ] 0
;[ embCfg - TopEmb Enable ] 1
;[ embCfg - StatEmb Enable ] 1
;[ embCfg - BotEmb Enable ] 1
;[ embCfg - DataType Enable ] 0
;[ fsinCfg - Fsync Enable ] 1
;[ fsinCfg - Fix Counter Enable ] 1
;[ expCfg - Preset Mode Enable ] 0
;[ Static White Balance AutoSwitch ] 1
OX08D10: OX08D10SetDeviceConfig - 30FPS
;[TpgEnabled] 0
;[charModeEnabled] 0
;[charModeExpNo  ] 0
;[ numFrameReportBytes ] 0
;[ nnumActiveExposures ] 4
;[ frameTiming - tclk ] 102083333
;[ frameTiming - hts ] 2476
;[ frameTiming - vts ] 1374
;[ frameTiming - hsize ] 3840
;[ frameTiming - vsize ] 2160
;[ frameTiming - binning ] 0
;[ frameTiming - timeLine ] 2.425470e-05
;[ frameTiming - fps ] 30.0066
;[ mfCfg - Mirror Enable ] 0
;[ mfCfg - Flip Enable ] 0
;[ embCfg - TopEmb Enable ] 1
;[ embCfg - StatEmb Enable ] 1
;[ embCfg - BotEmb Enable ] 1
;[ embCfg - DataType Enable ] 0
;[ fsinCfg - Fsync Enable ] 1
;[ fsinCfg - Fix Counter Enable ] 1
;[ expCfg - Preset Mode Enable ] 0
;[ Static White Balance AutoSwitch ] 1
terminate called after throwing an instance of 'std::runtime_error'
  what():  [2024-10-28 15:50:09] DW Error DW_INTERNAL_ERROR executing DW function:
 dwSensorManager_start(m_sensorManager)
 at /home/driveworks-5.20/samples/src/sensors/camera/camera2/main.cpp:80
Aborted
zhangzs@tegra-ubuntu:~/nvidia$

SensorManager works fine if I use only one camera, but when I use two, I have problems

@SivaRamaKrishnaNV

Dear @deng.shigang,
Note that, forum support is limited to support camera modules listed in DRIVE AGX Orin Sensors & Accessories | NVIDIA Developer .
Please confirm the camera module.

For initial debugging,

  1. Is the same camera working with sample_camera with out any code modification and just with updated camera-name entry in default rig,json used by sample?
  2. what is the sample_camera behavior when you add another camera entry with same params in the rig.json?
  3. Also, we need to make sure if nvsipl_camera is working well for the same camera configuration before trying DW.

@SivaRamaKrishnaNV

Our camera is the OX08D10 from OmniVision. We have not modified any of the code in sample_camera, and sample_camera is able to retrieve data from either or both cameras normally. We have also tested that nvsipl_camera works properly and can retrieve data from either or both cameras. The problem now is that when we write our own code to retrieve camera data through the SensorManager, the SensorManager can only retrieve data from one camera. When trying to retrieve data from both cameras, the function dwSensorManager_start fails. The same code worked without any issues in our testing on Drive OS 6.0.9.

Do you have any other supported camera modules to quickly test to confirm if indeed fails with other modules as well? This should confirm if the issue is limited to camera or a possible regression with sensormanager API.

We don’t have any other models of cameras available

@SivaRamaKrishnaNV any update?

Can you share your DW sample to retrieve data from two cameras. I will give a try with other camera modules.
Meanwhile, could you test if connecting second camera to other port works?

/////////////////////////////////////////////////////////////////////////////////////////
//
// Notice
// ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
// NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
// THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
// MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
//
// NVIDIA CORPORATION & AFFILIATES assumes no responsibility for the consequences of use of such
// information or for any infringement of patents or other rights of third parties that may
// result from its use. No license is granted by implication or otherwise under any patent
// or patent rights of NVIDIA CORPORATION & AFFILIATES. No third party distribution is allowed unless
// expressly authorized by NVIDIA. Details are subject to change without notice.
// This code supersedes and replaces all information previously supplied.
// NVIDIA CORPORATION & AFFILIATES products are not authorized for use as critical
// components in life support devices or systems without express written approval of
// NVIDIA CORPORATION & AFFILIATES.
//
// SPDX-FileCopyrightText: Copyright (c) 2019-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
// SPDX-License-Identifier: LicenseRef-NvidiaProprietary
//
// NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
// property and proprietary rights in and to this material, related
// documentation and any modifications thereto. Any use, reproduction,
// disclosure or distribution of this material and related documentation
// without an express license agreement from NVIDIA CORPORATION or
// its affiliates is strictly prohibited.
//
/////////////////////////////////////////////////////////////////////////////////////////

#include <dw/core/base/Version.h>
#include <dw/interop/streamer/ImageStreamer.h>
#include <dw/rig/Rig.h>
#include <dw/sensors/camera/Camera.h>
#include <dw/sensors/camera/CodecHeaderVideo.h>
#include <dw/sensors/Codec.h>
#include <dw/sensors/codecs/sensorserializer/SensorSerializer.h>

// SDK
#include <dw/core/base/Version.h>
#include <dw/calibration/engine/Engine.h>
#include <dw/sensors/sensormanager/SensorManager.h>

#include <limits>
#include <iostream>

// #######################################################################################
int main(int argc, const char **argv)
{
    dwContextHandle_t context = DW_NULL_HANDLE;
    dwContextParameters sdkParams = {};
    (dwInitialize(&context, DW_VERSION, &sdkParams));

    dwSALHandle_t sal = DW_NULL_HANDLE;
    (dwSAL_initialize(&sal, context));

    // the complete configuration is automatically loaded by dwRig module
    dwRigHandle_t m_rigConfig{};
    (dwRig_initializeFromFile(&m_rigConfig, context, "rig.json"));

    uint32_t m_cameraLeftSensorIdx = std::numeric_limits<decltype(m_cameraLeftSensorIdx)>::max();
    (dwRig_findSensorByName(&m_cameraLeftSensorIdx, "camera_sample0", m_rigConfig));

    uint32_t m_cameraRightSensorIdx = std::numeric_limits<decltype(m_cameraRightSensorIdx)>::max();
    (dwRig_findSensorByName(&m_cameraRightSensorIdx, "camera_sample1", m_rigConfig));

    dwSensorManagerHandle_t m_sensorManager = DW_NULL_HANDLE;

    dwSensorManagerParams smParams{};

    smParams.enableSensors[0] = m_cameraLeftSensorIdx;
    smParams.numEnableSensors++;

    smParams.enableSensors[1] = m_cameraRightSensorIdx;
    smParams.numEnableSensors++;

    // initialize Driveworks SensorManager directly from rig file
    (dwSensorManager_initializeFromRigWithParams(&m_sensorManager, m_rigConfig, &smParams, 1024, sal));

    (dwSensorManager_start(m_sensorManager));

    while (true)
    {
        std::cout << "in" << "\n";

        const dwSensorEvent *event = nullptr;
        dwImageHandle_t m_pendingFrame, m_pendingFrameLeft, m_pendingFrameRight;
        m_pendingFrame = m_pendingFrameLeft = m_pendingFrameRight = nullptr;

        bool get_data = false;

        while (!get_data)
        {
            dwCameraFrameHandle_t frames[2] = {DW_NULL_HANDLE, DW_NULL_HANDLE};
            dwStatus res = dwSensorManager_acquireNextEvent(&event, 1000, m_sensorManager);
            if (res == DW_SUCCESS)
            {
                switch (event->type)
                {
                case DW_SENSOR_CAMERA:
                    // Pass frames in left-right order
                    for (uint32_t i = 0; i < event->numCamFrames; ++i)
                    {
                        uint32_t idx = event->sensorIndices[i];
                        if (idx == m_cameraLeftSensorIdx)
                            frames[0] = event->camFrames[i];
                        else if (idx == m_cameraRightSensorIdx)
                            frames[1] = event->camFrames[i];
                    }

                    // handleCameras(frames);
                    dwImageHandle_t img_left;
                    (dwSensorCamera_getImage(&img_left, DW_CAMERA_OUTPUT_NATIVE_PROCESSED, frames[0]));

                    dwTime_t timestamp_left;
                    dwImage_getTimestamp(&timestamp_left, img_left);

                    //(dwSensorCamera_returnFrame(&frames[0]));

                    dwImageHandle_t img_rigth;
                    (dwSensorCamera_getImage(&img_rigth, DW_CAMERA_OUTPUT_NATIVE_PROCESSED, frames[1]));

                    dwTime_t timestamp_rigth;
                    dwImage_getTimestamp(&timestamp_rigth, img_rigth);

                    //(dwSensorCamera_returnFrame(&frames[1]));

                    // std::cout << timestamp_left - timestamp_rigth << "lll" << "\n";
                    std::cout << "1" << "\n";

                    get_data = true;

                    break;
                case DW_SENSOR_IMU:
                case DW_SENSOR_CAN:
                case DW_SENSOR_GPS:
                case DW_SENSOR_RADAR:
                case DW_SENSOR_TIME:
                case DW_SENSOR_LIDAR:
                case DW_SENSOR_DATA:
                case DW_SENSOR_COUNT:
                default:
                    break;
                }
            }
            else
            {
                std::cout << "0";
            }
        }

        if (event != nullptr)
        {
            (dwSensorManager_releaseAcquiredEvent(event, m_sensorManager));
            std::cout << "2" << "\n";
        }
    }

    return 1;
}

Dear @deng.shigang,
Thank you for sharing the sample code. I will test it and update you.

@SivaRamaKrishnaNV any update?

Dear @deng.shigang,
Firstly, noticed compilation error on DRIVE OS 6.0.10 docker.

/usr/local/driveworks/samples/src/sensors/camera/camera-byd/main.cpp:36:10: fatal error: dw/sensors/Codec.h: No such file or directory
   36 | #include <dw/sensors/Codec.h>

Added #include <dw/sensors/codecs/Codec.h> and added CHECK_DW_ERROR() to compile and able to repro the issue with your code using other camera modules as well on 6.0.10 where as the same rig.json was working well with sample_camera.

I could not check on older release. But as per your feedback the shared sample code snippet is working on older release.
I will investigate further with core team and update you. Also, Does your application development needs this functionality using sensor manager? Does it block your development?

Our team is in need of using this feature.
This won’t affect us, it would be great if you could fix it, so we can also upgrade to the latest version.

Dear @deng.shigang,
The patch for DW 5.20 can’t be released now if it is a bug and we suggest you to stick to working DW version if it is critical for your application development.

Dear @deng.shigang,
It is possible to share kernel logs when the issue occured with your camera modules. That helps engineering team to understand the route cause and fix it.

how to get the log?

Please check /var/log/syslog