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
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
Hello everyone,
In the future, I plan to record four videos using the DW API. I attempted to use dwSensorCamera_readFrame() to capture frames, which I would then store in a Serializer to create a video. However, the documentation for this function states, “Available data is configured during sensor creation.” As I understand it, this means that only one frame is captured when a (Camera-)Sensor is created.
My questions are:
How can I continuously capture new frames?
Are there any stitching algorithms from NVIDIA that I can use to create a BirdView perspective from the videos?
Could you clarify the issue? Do you see any frame drop when trying to serialize the camera frames?
Note that, if the storage does not have enough write speed, you would expect to see frame drop messages.
Please check with recording with recorder tool first to get an idea on the limitations. You can record for 10 secs and see number of timestamps(frames) captured.
The problem is, that everytime (during the runtime of my program) I call the function dwSensorCamera_readFrame() I got the same Image. The Image is only created once during sensor creation. The serialization of the Images isn’t currently necessary. My focus now, is to write a program where I can for example press the key 1 on the keyboard and then take a new picture.
The return value should be DW_SUCCESS, since I run every API call with CHECK_DW_ERROR() and I didn’t get a warning or something like this.
Currently I dont need to serialize frames, I want to run a superloop, which generates every time a new frame, when I press “1”.
My question is, if there is another way to generate frames during the runtime of my program, as the Sensors are only created at the beginning of my program?
// Specifiy the gmsl protocol for the first camera
m_senParams[0].parameters =
“camera-name=C2SIM623S2RU1195NB20,interface=csi-cd,CPHY-mode=1,”
“link=0,output-format=processed,skip-eeprom=1,fifo-size=1”;
m_senParams[0].protocol = “camera.gmsl”;
// Specifiy the gmsl protocol for the second camera
m_senParams[1].parameters =
“camera-name=C2SIM623S2RU1195NB20,interface=csi-cd,CPHY-mode=1,”
“link=1,output-format=processed,skip-eeprom=1”;
m_senParams[1].protocol = “camera.gmsl”;
// Specifiy the gmsl protocol for the third camera
m_senParams[2].parameters =
“camera-name=C2SIM623S2RU1195NB20,interface=csi-cd,CPHY-mode=1,”
“link=2,output-format=processed,skip-eeprom=1”;
m_senParams[2].protocol = “camera.gmsl”;
// Specifiy the gmsl protocol for the fourth camera
m_senParams[3].parameters =
“camera-name=C2SIM623S2RU1195NB20,interface=csi-cd,CPHY-mode=1,”
“link=3,output-format=processed,skip-eeprom=1,fifo-size=1”;
m_senParams[3].protocol = “camera.gmsl”;
// Create the sensor (here: camera)
for (int i = 0; i < MAX_CAMS; i++) {
CHECK_DW_ERROR(dwSAL_createSensor(&m_camera[i], m_senParams[i], m_sal));
}
// Start the Sensor Abstraction Layer
CHECK_DW_ERROR(dwSAL_start(m_sal));
// Start the sensor (here: camera)
for (int i = 0; i < MAX_CAMS; i++) {
CHECK_DW_ERROR(dwSensor_start(m_camera[i]));
}
}
void CCameraSample::initImageStreamer() {
// Get the CUDA Image Properties
dwImageProperties cudaProp { };
CHECK_DW_ERROR(
dwSensorCamera_getImageProperties(&cudaProp, DW_CAMERA_OUTPUT_CUDA_RGBA_UINT8, m_camera[FIRST_CAMERA_IDX]));
// has to be called twice
for (int i = 0; i < MAX_CAMS; i++) {
dwCameraFrameHandle_t frameHandle = DW_NULL_HANDLE;
CHECK_DW_ERROR(dwSensorCamera_readFrame(&frameHandle, timeout, m_camera[i]));
// Create a image out of the taken Frame
dwImageHandle_t imageHandle = DW_NULL_HANDLE;
CHECK_DW_ERROR(
dwSensorCamera_getImage(&imageHandle,
DW_CAMERA_OUTPUT_CUDA_RGBA_UINT8, frameHandle));
// Passes the Image to the Image-Streamer
exportImage(imageHandle, i);
// Releasing the handles
CHECK_DW_ERROR(dwSensorCamera_returnFrame(&frameHandle));
}
}
void CCameraSample::run() {
bool abortApp = false;
while (!abortApp) {
switch (m_choice) {
case SINGLE:
getFrame();
displayMenu();
m_choice = WAIT;
break;
case ONGOING:
startVideo();
displayMenu();
m_choice = WAIT;
break;
case QUIT:
releaseHandle();
abortApp = true;
break;
case STOP:
break;
case WAIT:
readInput();
break;
case INVALID:
cerr << getCurrentTime().str() << "Invalid Option. Try again.\n";
displayMenu();
m_choice = WAIT;
break;
}
for (int i = 0; i < MAX_CAMS; i++) {
// Stop the camera
CHECK_DW_ERROR(dwSensor_stop(m_camera[i]));
cout << getCurrentTime().str() << "CameraClient: Client stopped - Link "
<< i << endl;
// Release camera sensor
CHECK_DW_ERROR(dwSAL_releaseSensor(m_camera[i]));
cout << getCurrentTime().str() << "Camera master released - Link " << i
<< endl;
}
// Release SAL module of the SDK
CHECK_DW_ERROR(dwSAL_release(m_sal));
cout << getCurrentTime().str() << “Driveworks SDK released” << endl;
}