Encoding processed images with DriveWorks 6.0.6

DRIVE OS Version: 6.0.6.0-32441545

Issue Description: We’re trying to encode processed images with H265 or H264.

Hello Nvidia Forum Support,

we are developing an application with an Nvidia Drive AGX Orin device to read out multiple cameras, do some processing like scaling and rectifying. We then want to send the processed images to another device (Nvidia Drive AGX Thor) which should display the multiple processed images as videos.

Currently, we are struggling with the encoding part. We want to use H265 (H264 would be acceptable too but we prefer H265), it’s not clear to us how we can encode the images.

At first, we wanted to use the API like in the Sensor Serialization / Camera Encoding Tutorial, but unfortunately, this tutorial does not match the actual API, since the dwSensorSerializer_serializeCameraFrameAsync function does not take a dwImageHandle_t but a dwCameraFrameHandle_t. But our processed images work with dwImageHandle_t so we can’t use this serialization. We’re also not really trying to serialize a sensor but to encode our processed images.

Because of this, we are now trying to use nvmedia’s image encoder, but it’s not quite clear to us how to actually integrate this into our application. After creating the NvMediaEncodeInitializeParamsH265, using NvSciBufModuleOpen and creating a NvSciBufAttrList and filling it, the NvMediaIEPCreate returns a nullpointer. I believe the error my in not filling that NviSciBufAttrList correctly, but don’t know how to do it correctly.

We use this method to try and create the nvmedia encoder:

void Encoder::initialize_nvmedia_encoder() {
// The documentation says getting the version is a precondition. That
// makes no sense to me but whatever.
NvMediaVersion \_version;  // unused
CHECK_NVMEDIA(NvMediaIEPGetVersion(&\_version),
“could not get nvmedia IEP version”);

// We create an encoder of type HEVC, this requires a
// NvMediaEncodeInitializeParamsH265 as the parameter struct.
NvMediaEncodeInitializeParamsH265 params = {};  // TODO: create params

// this is some nv sci buffer container that we need
this->nv_module = nullptr;

CHECK_NVSCI(NvSciBufModuleOpen(&this->nv_module), “could not open nv_module”);

// this is a list of attributes which tells nvmedia how to allocate some
// kind of memory.
this->nv_attrlist =
nullptr;  // this is a pointer type, set by the next function call

CHECK_NVSCI(NvSciBufAttrListCreate(this->nv_module, &this->nv_attrlist),
“could not create nv_attrlist”);

CHECK_NVMEDIA(NvMediaIEPFillNvSciBufAttrList(NVMEDIA_ENCODER_INSTANCE_0,
this->nv_attrlist),
“could not prepare NvSciBufAttrList”);

// BUG: for some reason this currently always returns a nullpointer
NvMediaIEP\* encoder = NvMediaIEPCreate(
NVMEDIA_IMAGE_ENCODE_HEVC, &params, this->nv_attrlist,
settings::encoding::ENCODING_MAX_BUFFERING, NVMEDIA_ENCODER_INSTANCE_0);

if (nullptr == encoder) {
throw std::runtime_error(“Encoder could not be initialized!”);
}

this->nv_encoder = encoder;
}

It would be very appreciated if you could help me understand how to encode image data from a dwImageHandle_t .

Greetings,

Christoph

1 Like

Dear @christoph.scherr ,
May I know if you have any dependency on DOS 6.0.6 or can be upgraded to latest DOS 6.0.10 release?
Is the application like readCamera → scale image resolution → encode → transfer image data via ethernet → display on second orin?

Firstly, check https://developer.nvidia.com/docs/drive/drive-os/6.0.10/public/drive-os-linux-sdk/common/topics/nvmedia_sample_apps/NvMediaIEPEncodeProcessing_nvm_iep_sci_1.html to know the FPS you can achieve for a input resolution for HP encoding. This helps to get am idea of how many cameras can be encoded at a time.

Hi. We have to use 6.0.6 because our cameras are no longer supported in the more recent versions. (Our cameras are F003A/AR0233 2.6MP cameras, from Entron)

You got the chain of the application right, except that we will display the images from the camera with a thor device:

readCamera → scale image resolution/crop/rectify/other processing → encode → transfer image data via ethernet → receive the data on our thor system → decode → display

For the encoding sample: I not sure where to get a yuv file. I tried it with a test image from this public repository: test-images/images at main · make87/test-images · GitHub and it seems to have worked?

nvdev@tegra-ubuntu:~/nvmedia_6x/iep$ ./nvm_iep_sci -cf testh265.cfg

Total encoded frames = 2, avg. bitrate=22058400, maxBitrate=0, minBitrate=-8

***ENCODING PROCESS ENDED SUCCESSFULY***
nvmedia: ERROR: Error while retrieving taskStatus from fence
nvmedia: ERROR: TaskStatus shows 65535
nvmedia: ERROR: Error while retrieving taskStatus from fence
nvmedia: ERROR: TaskStatus shows 65535
nvmedia: ERROR: Error while retrieving taskStatus from fence
nvmedia: ERROR: TaskStatus shows 65535
total failures: 0

I also saw that there is some source code provided with that example application that uses the nvmedia encoder, but it’s source code is difficult to understand (the main function alone is about 1500 lines).

Hello, an update on this matter would be appreciated. I’m still trying to get image encoding to work with nvmedia but not succeeding, and it’s blocking our application development.

@SivaRamaKrishnaNV could you maybe point me in the right direction for image encoding on drive os 6.0.6? If image encoding is in general not supported or possible, at least knowing this would help as well.

Besides using nvmedia, perhaps it is possible to create a sort of virtual camera with our images, or to use the Image Capture API as a workaround.

Greetings.

Regarding the last supported DRIVE OS version, have you verified with onsemi?

You can generate yuv using nvsipl_camera. Please see Command Line Switches | NVIDIA Docs . You can use -f option to store ISP output in yuv file.

NvMedia IEP sample gives expected perf numbers for the needed encoding type for camera module. Make sure to use correct input and output resolution and encoding type(you can check with HP mode) in config file.

FYI, GMSL params has ispX-res to scale the input image to specific resolution from ISP. We have dwEncoder API to perform encoding directly instead of relying the DW serializer API. But we don’t have a sample demonstrating the usage in DOS 6.0.6.

I see. Thanks for the quick response and clearing the matters with that example program up.

Regarding the dwEncoder API and the example code you private messaged me, unfortunately, it seems like the dwEncoder API is a recent addition to the driveworks SDK (perhaps in DriveWorks 7?).

It is available here: DriveWorks 7.0.3 API Documentation (Draft) but not in the version we use: DriveWorks 6.0.6 API Documentation, so it unfortunately seems like I can’t make use of this.

Even in the newer 6.0.10 version of the DriveWorks API (which we can’t use because of the camera drivers not being compatible), there seems to be only a configuration for the encoder, but I’m not sure about this one.

Dear @christoph.scherr ,
I notice DOS 6.0.6 does not have dwEncoder API to perform encoding directly. I can see them in DOS 6.0.10 though documentation missed to list it.

root@6.0.10.0-0009-build-linux-sdk:/usr/local/driveworks# grep -lir "dwEncoder_encode" *
include/dw/sensors/codecs/Encoder.h

DOS 6.0.6 has encoding only via dwSerialization APIs. Please check using isp0-res GMSL params to scale the image and evaluate the use case accordingly.

Could you please provide any update for this topic?

Hello. I apologize for not answering earlier, i was sick.

As our cameras do not work with a drive os version beyond 6.0.6, this is making development difficult for us. The serializtation API works but if we use it, we currently need to choose between encoding and image processing (since processed images aka frames cannot be encoded).

Do you know of a workaround to get the encoding of processed images on drive os 6.0.6 working? Perhaps feeding our processed images into a virtual camera sensor and serializing the images from that virtual sensor? Perhaps using nvmedia directly? Perhaps with some other library?

Help would be appreciated.

Hello, could we please get an update on this? We are still hoping for a workaround on how to encode processed imaged with driveworks 6.0.6. Any help would be appreciated.

You can try this. Store the processed image video and load it again later in another application using virtual sensor and use serialization APIs to perform encoding.

This will not work. Using the serializer API with virtual cameras does not encode our images but return an undocumented “NOT IMPLEMENTED” status.

How about combining DriveWorks SDK Reference: Video Rectification Sample and sample_camera? sample_camera can scale the input video and rectifier sample works on encoded video and generates encoded output stream.
If this does not work, you need to explore application development with NvMedia APIs directly as in DW 5.10 encoding can not be done alone.

Hi @SivaRamaKrishnaNV , I’m a colleague of @christoph.scherr and was trying to implement said behavior by using the FrameCapture API used by the rectification sample, but I always get this undocumented error, regardless, whether I use the serializer callback or “save to file”:

terminate called after throwing an instance of 'std::runtime_error'
  what():  [2026-02-20 10:06:05] DW Error DW_NOT_AVAILABLE executing DW function:
 dwFrameCapture_appendFrame(image, frameCapture)
 at /workspace/vcu/apps/src/ntvcu/src/main_video_recorder.cpp:109
Aborted

Here is the main-function I wrote:

#include <cstdint>
#include <framework/Log.hpp>

#include "dw/core/base/Types.h"
#include "dw/image/Image.h"
#include "dw/sensors/Sensors.h"
#include "dw/sensors/camera/Camera.h"
#include "dw/sensors/sensormanager/SensorManager.h"
#include "dwvisualization/core/Visualization.h"
#include "dwvisualization/image/FrameCapture.h"
#include "dwvisualization/image/FrameCaptureExtra.h"
#include "framework/Checks.hpp"
#include "unistd.h"

int main(int argc, char const* argv[]) {
  dwContextHandle_t sdk = DW_NULL_HANDLE;
  dwContextParameters sdkParams = {};
  dwVersion sdkVersion;
  dwSALHandle_t sal = DW_NULL_HANDLE;
  dwVisualizationContextHandle_t vis = DW_NULL_HANDLE;
  dwSensorManagerHandle_t sensorManager = DW_NULL_HANDLE;
  dwRigHandle_t rig = DW_NULL_HANDLE;
  dwSerializerParams serializerParams{};
  dwFrameCaptureParams frameCaptureParams{};
  dwFrameCaptureHandle_t frameCapture = DW_NULL_HANDLE;
  dwGetVersion(&sdkVersion);
  dwInitialize(&sdk, sdkVersion, &sdkParams);
  CHECK_DW_ERROR(dwSAL_initialize(&sal, sdk));
  CHECK_DW_ERROR(dwVisualizationInitialize(&vis, sdk));
  CHECK_DW_ERROR(dwRig_initializeFromFile(&rig, sdk, argv[2]));
  CHECK_DW_ERROR(
      dwSensorManager_initializeFromRig(&sensorManager, rig, 16, sal));
  std::cout << "Context of Driveworks SDK successfully initialized."
            << std::endl;
  std::cout << "Version: " << sdkVersion.major << "." << sdkVersion.minor << "."
            << sdkVersion.patch << std::endl;
  dwImageTransformationHandle_t imageTransformationEngine =
      initImageTransformationEngine(sdk);
  // frameCaptureParams.params.parameters =
  //     "format=h264,bitrate=800000,framerate=30,type=disk,file=frameCapture."
  //     "h264";
  serializerParams.onData = OnSerializerData;
  serializerParams.parameters =
      "type=user,format=h264,bitrate=800000,framerate=30";
  frameCaptureParams.params = serializerParams;
  frameCaptureParams.mode = DW_FRAMECAPTURE_MODE_SERIALIZE;
  frameCaptureParams.width = 1920;
  frameCaptureParams.height = 1080;
  CHECK_DW_ERROR(
      dwFrameCapture_initialize(&frameCapture, &frameCaptureParams, sal, sdk));
  CHECK_DW_ERROR(dwSAL_start(sal));
  CHECK_DW_ERROR(dwSensorManager_start(sensorManager));
  CHECK_DW_ERROR(dwFrameCapture_start(frameCapture));
  do {
    const dwSensorEvent* acquired_event = nullptr;
    auto status =
        dwSensorManager_acquireNextEvent(&acquired_event, 0, sensorManager);
    if (status == DW_TIME_OUT) return 1;
    if (acquired_event->type == DW_SENSOR_CAMERA) {
      auto frame = acquired_event->camFrames[acquired_event->sensorTypeIndex];
      if (frame) {
        dwImageHandle_t image = DW_NULL_HANDLE;
        dwSensorCamera_getImage(&image, DW_CAMERA_OUTPUT_CUDA_RGBA_UINT8,
                                frame);
        if (image) {
          CHECK_DW_ERROR(dwFrameCapture_appendFrame(image, frameCapture));
        }
      }

    } else {
      usleep(1000);
    }
    CHECK_DW_ERROR(
        dwSensorManager_releaseAcquiredEvent(acquired_event, sensorManager));
  } while (running);

  CHECK_DW_ERROR(dwRig_release(rig));
  std::cout << "dwRig_release() successful" << std::endl;
  CHECK_DW_ERROR(dwFrameCapture_stop(frameCapture));
  std::cout << "dwSensorSerializer_stop() successful" << std::endl;
  CHECK_DW_ERROR(dwFrameCapture_release(frameCapture));
  std::cout << "dwSensorSerializer_release() successful" << std::endl;
  CHECK_DW_ERROR(dwSAL_release(sal));
  std::cout << "dwSAL_release() successful" << std::endl;
  CHECK_DW_ERROR(dwImageTransformation_release(imageTransformationEngine));
  std::cout << "dwImageTransformation_release() successful" << std::endl;
  CHECK_DW_ERROR(dwVisualizationRelease(vis));
  std::cout << "dwVisualisation_release() successful" << std::endl;
  CHECK_DW_ERROR(dwRelease(sdk));
  std::cout << "dwRelease() successful" << std::endl;
  return 0;
}

I tried various combinations and ways to retrieve an image from the camera, but none worked. Can you spot any mistake?

1 Like

Quick update for anyone with the same problem: for some reason, the dwFrameCapture_start() function is not necessary or faulty. When left away, the code works fine

1 Like

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.