DriveWorks SDK Reference

| 0.6.67 Release

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 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 
47 #ifndef DW_SENSORS_CAMERA_CAMERA_H__
48 #define DW_SENSORS_CAMERA_CAMERA_H__
49 
50 #include <dw/core/Config.h>
51 #include <dw/core/Types.h>
52 
53 #include <dw/sensors/Sensors.h>
54 
55 #include <dw/image/Image.h>
56 
57 #ifdef __cplusplus
58 extern "C" {
59 #endif
60 
62 typedef struct dwCameraFrame *dwCameraFrameHandle_t;
63 
65 typedef enum dwCameraOutputType {
70 
71 typedef enum dwCameraRawFormat {
74 
79 
84 
90 
92 typedef enum dwCameraType {
108 } dwCameraType;
109 
110 typedef struct dwCameraProperties {
112  uint32_t siblings;
113  int32_t outputTypes;
118 
142 dwStatus dwSensorCamera_readFrame(dwCameraFrameHandle_t *frameHandle, uint32_t sibling,
143  dwTime_t timeout_us, dwSensorHandle_t sensor);
144 
145 
159 dwStatus dwSensorCamera_returnFrame(dwCameraFrameHandle_t *frameHandle);
160 
161 
162 
177 dwStatus dwSensorCamera_getDataLines(const dwImageDataLines **dataLines, dwCameraFrameHandle_t frameHandle);
178 
198  dwCameraFrameHandle_t frameHandle);
199 
200 
219  dwCameraFrameHandle_t frameHandle);
220 
221 
231  dwSensorHandle_t sensor);
232 
246  dwCameraOutputType type,
247  dwSensorHandle_t sensor);
248 
260 dwStatus dwSensorCamera_getTimestamp(dwTime_t* timestamp, dwCameraFrameHandle_t frameHandle);
261 
262 #ifdef __cplusplus
263 }
264 #endif
265 
266 // OS-specific
267 #ifdef VIBRANTE
268 #include "Camera_vibrante.h"
269 #endif
270 
271 #endif // DW_SENSORS_CAMERA_CAMERA_H__
dwCameraRawFormat rawFormat
Definition: Camera.h:116
NVIDIA DriveWorks API: Core Types
float float32_t
Specifies POD types.
Definition: Types.h:77
Container for data lines from the camera.
Definition: Image.h:170
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:115
Defines a CUDA image.
Definition: Image.h:263
DW_API_PUBLIC dwStatus dwSensorCamera_getImageCUDA(dwImageCUDA **image, dwCameraOutputType format, dwCameraFrameHandle_t frameHandle)
Gets a frame from the camera sensor.
DW_API_PUBLIC dwStatus dwSensorCamera_getImageCPU(dwImageCPU **image, dwCameraOutputType format, dwCameraFrameHandle_t frameHandle)
Gets a frame from the camera sensor.
uint64_t dwTime_t
Specifies a timestamp unit, in microseconds.
Definition: Types.h:89
DW_API_PUBLIC dwStatus dwSensorCamera_getTimestamp(dwTime_t *timestamp, dwCameraFrameHandle_t frameHandle)
Gets the timestamp of the current camera frame.
dwCameraType
Enum of available cameras.
Definition: Camera.h:92
NVIDIA DriveWorks API: Image Conversion and Streaming Functionality
struct dwSensorObject * dwSensorHandle_t
Handle representing a sensor.
Definition: Sensors.h:80
dwStatus
Status definition.
Definition: Status.h:167
NVIDIA DriveWorks API: Sensors
DW_API_PUBLIC dwStatus dwSensorCamera_getDataLines(const dwImageDataLines **dataLines, dwCameraFrameHandle_t frameHandle)
Gets the data lines sent by the camera sensor.
DW_API_PUBLIC dwStatus dwSensorCamera_getImageProperties(dwImageProperties *imageProperties, dwCameraOutputType type, dwSensorHandle_t sensor)
Gets information about the image properties for a given dwCameraOutputType.
Defines a two-element unsigned-integer vector.
Definition: Types.h:219
dwCameraType cameraType
Definition: Camera.h:114
struct dwCameraFrame * dwCameraFrameHandle_t
Handle to captured frame.
Definition: Camera.h:62
int32_t outputTypes
Definition: Camera.h:113
DW_API_PUBLIC dwStatus dwSensorCamera_getSensorProperties(dwCameraProperties *properties, dwSensorHandle_t sensor)
Gets information about the camera sensor.
NVIDIA DriveWorks API: Vibrante Cameras
DW_API_PUBLIC dwStatus dwSensorCamera_readFrame(dwCameraFrameHandle_t *frameHandle, uint32_t sibling, dwTime_t timeout_us, dwSensorHandle_t sensor)
Reads a frame handle from the camera sensor.
uint32_t siblings
Definition: Camera.h:112
float32_t framerate
Definition: Camera.h:111
dwCameraOutputType
Output types supported by the camera.
Definition: Camera.h:65
dwCameraRawFormat
Definition: Camera.h:71
#define DW_API_PUBLIC
Definition: Exports.h:76
Raw encoding formats pixel-order.
Definition: Camera.h:73
Defines the properties of the image.
Definition: Image.h:220
Defines a CPU-based image.
Definition: Image.h:239