DriveWorks SDK Reference
4.0.0 Release
For Test and Development only

Camera.h
Go to the documentation of this file.
1 // This code contains NVIDIA Confidential Information and is disclosed
3 // under the Mutual Non-Disclosure Agreement.
4 //
5 // Notice
6 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
7 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
8 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
9 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
10 //
11 // NVIDIA Corporation assumes no responsibility for the consequences of use of such
12 // information or for any infringement of patents or other rights of third parties that may
13 // result from its use. No license is granted by implication or otherwise under any patent
14 // or patent rights of NVIDIA Corporation. No third party distribution is allowed unless
15 // expressly authorized by NVIDIA. Details are subject to change without notice.
16 // This code supersedes and replaces all information previously supplied.
17 // NVIDIA Corporation products are not authorized for use as critical
18 // components in life support devices or systems without express written approval of
19 // NVIDIA Corporation.
20 //
21 // Copyright (c) 2016-2021 NVIDIA Corporation. All rights reserved.
22 //
23 // NVIDIA Corporation and its licensors retain all intellectual property and proprietary
24 // rights in and to this software and related documentation and any modifications thereto.
25 // Any use, reproduction, disclosure or distribution of this software and related
26 // documentation without an express license agreement from NVIDIA Corporation is
27 // strictly prohibited.
28 //
30 
51 #ifndef DW_SENSORS_CAMERA_CAMERA_H_
52 #define DW_SENSORS_CAMERA_CAMERA_H_
53 
54 #include <dw/core/Config.h>
55 #include <dw/core/base/Types.h>
56 #include <dw/sensors/Sensors.h>
57 #include <dw/image/Image.h>
58 
59 // Forward declares from NvMedia
60 typedef void NvMediaIPPManager;
61 
62 #ifdef __cplusplus
63 extern "C" {
64 #endif
65 
67 typedef struct dwCameraFrame* dwCameraFrameHandle_t;
68 
72 typedef enum dwCameraOutputType {
91 
93 typedef enum dwCameraRawFormat {
95 
100 
105 
110 
112 
115 
117 typedef enum dwCameraType {
129 } dwCameraType;
130 
144 
146 typedef enum dwCameraFOV {
159 } dwCameraFOV;
160 
162 typedef struct dwCameraProperties
163 {
166  dwCameraExposureControl exposure;
170  int32_t outputTypes;
171  uint32_t siblings;
172  uint32_t revision;
173  uint32_t imageBitDepth;
174  bool isSimulated;
176 
211 dwStatus dwSensorCamera_readFrame(dwCameraFrameHandle_t* frameHandle,
212  dwTime_t timeout_us, dwSensorHandle_t sensor);
213 
229 dwStatus dwSensorCamera_returnFrame(dwCameraFrameHandle_t* frameHandle);
230 
255  dwCameraFrameHandle_t frame);
256 
281  dwCameraFrameHandle_t frame);
282 
298 
312  dwSensorHandle_t sensor);
313 
327  dwSensorHandle_t sensor);
328 
343  uint32_t modeIdx,
344  dwSensorHandle_t sensor);
345 
364  dwCameraOutputType type,
365  dwSensorHandle_t sensor);
366 
379 dwStatus dwSensorCamera_setCUDAStream(cudaStream_t stream, dwSensorHandle_t sensor);
380 
392 dwStatus dwSensorCamera_getCUDAStream(cudaStream_t* stream, dwSensorHandle_t sensor);
393 
405 dwStatus dwSensorCamera_getTimestamp(dwTime_t* timestamp, dwCameraFrameHandle_t frameHandle);
406 
407 #ifdef __cplusplus
408 }
409 #endif
410 
411 #endif // DW_SENSORS_CAMERA_CAMERA_H_
NVIDIA DriveWorks API: Core Types
dwCameraRawFormat rawFormat
Definition: Camera.h:165
float float32_t
Specifies POD types.
Definition: Types.h:70
DW_API_PUBLIC dwStatus dwSensorCamera_getNvMediaIPPManager(NvMediaIPPManager **manager, dwSensorHandle_t sensor)
Gets the NvMediaIPPManager used for GMSL camera IPP setup and event callback.
struct dwImageObject * dwImageHandle_t
Definition: Image.h:100
dwCameraExposureControl
Enum of exposure control types.
Definition: Camera.h:132
DW_API_PUBLIC dwStatus dwSensorCamera_setCUDAStream(cudaStream_t stream, dwSensorHandle_t sensor)
Sets the CUDA stream used by getImageAsync during internal cuda related operations.
DW_API_PUBLIC dwStatus dwSensorCamera_returnFrame(dwCameraFrameHandle_t *frameHandle)
Returns a frame to the camera after it has been consumed.
dwVector2ui resolution
Definition: Camera.h:169
Exposure control using user&#39;s custom callback.
Definition: Camera.h:142
Default exposure control.
Definition: Camera.h:138
DW_API_PUBLIC dwStatus dwSensorCamera_getTimestamp(dwTime_t *timestamp, dwCameraFrameHandle_t frameHandle)
Gets the timestamp of the current camera frame.
NVIDIA DriveWorks API: Image Conversion and Streaming Functionality
DW_API_PUBLIC dwStatus dwSensorCamera_getImageAsync(dwImageHandle_t *image, dwCameraOutputType type, dwCameraFrameHandle_t frame)
Gets the output image/s image in a format specified by the output type.
DW_API_PUBLIC dwStatus dwSensorCamera_readFrame(dwCameraFrameHandle_t *frameHandle, dwTime_t timeout_us, dwSensorHandle_t sensor)
Reads a frame handle from the camera sensor.
dwCameraType
Enum of available camera sensors.
Definition: Camera.h:117
void NvMediaIPPManager
Definition: Camera.h:60
DW_API_PUBLIC dwStatus dwSensorCamera_getNumSupportedCaptureModes(uint32_t *numModes, dwSensorHandle_t sensor)
Gets number of supported capture modes.
struct dwSensorObject * dwSensorHandle_t
Handle representing a sensor.
Definition: Sensors.h:84
dwStatus
Status definition.
Definition: Status.h:180
NVIDIA DriveWorks API: Sensors
other YUV processed outputs (see devguide)
Definition: Camera.h:89
int64_t dwTime_t
Specifies a timestamp unit, in microseconds.
Definition: Types.h:82
for processed images RGBA image supported in all processed use cases
Definition: Camera.h:79
dwCameraFOV
Enum of available FOV in degrees for camera lenses.
Definition: Camera.h:146
dwCameraFOV fov
Definition: Camera.h:168
DW_API_PUBLIC dwStatus dwSensorCamera_getImageProperties(dwImageProperties *imageProperties, dwCameraOutputType type, dwSensorHandle_t sensor)
Gets information about the image properties for a given &#39;dwCameraImageOutputType&#39;.
Defines a two-element unsigned-integer vector.
Definition: Types.h:312
dwCameraType cameraType
Definition: Camera.h:164
simple yuv420 output, supported in most use cases (see doc)
Definition: Camera.h:81
Unknown exposure control.
Definition: Camera.h:136
struct dwCameraFrame * dwCameraFrameHandle_t
Handle to captured frame.
Definition: Camera.h:67
int32_t outputTypes
Definition: Camera.h:170
Camera Properties.
Definition: Camera.h:162
No exposure control.
Definition: Camera.h:134
DW_API_PUBLIC dwStatus dwSensorCamera_getSensorProperties(dwCameraProperties *properties, dwSensorHandle_t sensor)
Gets information about the camera sensor.
uint32_t siblings
Definition: Camera.h:171
float32_t framerate
Definition: Camera.h:167
dwCameraOutputType
Output types supported by the camera.
Definition: Camera.h:72
other YUV processed outputs (see devguide)
Definition: Camera.h:85
other YUV processed outputs (see devguide)
Definition: Camera.h:87
uint32_t revision
Definition: Camera.h:172
uint32_t imageBitDepth
Definition: Camera.h:173
dwCameraExposureControl exposure
Definition: Camera.h:166
dwCameraRawFormat
Raw encoding formats pixel-order.
Definition: Camera.h:93
DW_API_PUBLIC dwStatus dwSensorCamera_getCUDAStream(cudaStream_t *stream, dwSensorHandle_t sensor)
Gets the CUDA stream used.
DW_API_PUBLIC dwStatus dwSensorCamera_getImage(dwImageHandle_t *image, dwCameraOutputType type, dwCameraFrameHandle_t frame)
Gets the output image/s image in a format specified by the output type.
#define DW_API_PUBLIC
Definition: Exports.h:54
processed images (usually be YUV420 planar or RGB planar)
Definition: Camera.h:74
Defines the properties of the image.
Definition: Image.h:238
DW_API_PUBLIC dwStatus dwSensorCamera_getSupportedCaptureMode(dwCameraProperties *captureMode, uint32_t modeIdx, dwSensorHandle_t sensor)
Gets capture modes by specified index.
Exposure control with bracketed auto exposure.
Definition: Camera.h:140