DriveWorks SDK Reference
4.0.0 Release
For Test and Development only

CameraModel.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) 2015-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 
31 #ifndef DW_CALIBRATION_CAMERAMODEL_CAMERAMODEL_H_
32 #define DW_CALIBRATION_CAMERAMODEL_CAMERAMODEL_H_
33 
34 #include <dw/core/Config.h>
36 #include <dw/core/base/Exports.h>
37 #include <dw/core/base/Types.h>
38 #include <dw/rig/Rig.h>
39 
40 #ifdef __cplusplus
41 extern "C" {
42 #endif
43 
59 // Calibrated cameras
61 
66 typedef struct dwCameraModelObject* dwCameraModelHandle_t;
67 
70 typedef struct dwCameraModelObject const* dwConstCameraModelHandle_t;
71 
84 dwStatus dwCameraModel_initializePinhole(dwCameraModelHandle_t* obj,
85  const dwPinholeCameraConfig* config,
86  dwContextHandle_t context);
87 
104 DW_DEPRECATED("OCam support will be removed from Driveworks in an upcoming release. Use FTheta instead.")
105 dwStatus dwCameraModel_initializeOCam(dwCameraModelHandle_t* obj,
106  const dwOCamCameraConfig* config,
107  dwContextHandle_t context);
108 
121 dwStatus dwCameraModel_initializeFTheta(dwCameraModelHandle_t* obj,
122  const dwFThetaCameraConfig* config,
123  dwContextHandle_t context);
124 
137 dwStatus dwCameraModel_initializeStereographic(dwCameraModelHandle_t* obj,
138  const dwStereographicCameraConfig* config,
139  dwContextHandle_t context);
140 
153 dwStatus dwCameraModel_release(dwCameraModelHandle_t obj);
154 
174  dwCameraModelHandle_t obj);
175 
193  float32_t u, float32_t v,
194  dwConstCameraModelHandle_t obj);
195 
212  float32_t x, float32_t y, float32_t z,
213  dwConstCameraModelHandle_t obj);
214 
239 dwStatus dwCameraModel_isRayInsideFOV(bool* isInsideMaxFOV,
240  float32_t x, float32_t y, float32_t z,
241  dwConstCameraModelHandle_t obj);
242 
255  dwConstCameraModelHandle_t obj);
256 
269 dwStatus dwCameraModel_getImageSize(uint32_t* width, uint32_t* height,
270  dwConstCameraModelHandle_t obj);
271 
320  dwVector2ui newSize,
321  dwCameraModelHandle_t obj);
322 
339 dwStatus dwCameraModel_initialize(dwCameraModelHandle_t* camera,
340  uint32_t sensorId,
341  dwConstRigHandle_t obj);
342 
345 #ifdef __cplusplus
346 }
347 #endif
348 
349 #endif // DW_CALIBRATION_CAMERAMODEL_CAMERAMODEL_H_
NVIDIA DriveWorks API: Core Types
DW_API_PUBLIC dwStatus dwCameraModel_getHorizontalFOV(float32_t *hfov, dwConstCameraModelHandle_t obj)
Gets the horizontal Field of View (FOV) of the calibrated camera, in radians.
float float32_t
Specifies POD types.
Definition: Types.h:70
NVIDIA DriveWorks API: Rig Configuration
DW_API_PUBLIC dwStatus dwCameraModel_initializeFTheta(dwCameraModelHandle_t *obj, const dwFThetaCameraConfig *config, dwContextHandle_t context)
Creates and initializes a calibrated camera for the F-Theta distortion model.
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:227
DW_API_PUBLIC dwStatus dwCameraModel_initializeStereographic(dwCameraModelHandle_t *obj, const dwStereographicCameraConfig *config, dwContextHandle_t context)
Creates and initializes a calibrated stereographic camera.
DW_API_PUBLIC dwStatus dwCameraModel_pixel2Ray(float32_t *x, float32_t *y, float32_t *z, float32_t u, float32_t v, dwConstCameraModelHandle_t obj)
Back-projects a 2D point in pixel coordinates to a 3D optical ray direction.
DW_API_PUBLIC dwStatus dwCameraModel_initializePinhole(dwCameraModelHandle_t *obj, const dwPinholeCameraConfig *config, dwContextHandle_t context)
Creates and initializes a calibrated pinhole camera.
dwStatus
Status definition.
Definition: Status.h:180
DW_API_PUBLIC dwStatus dwCameraModel_isRayInsideFOV(bool *isInsideMaxFOV, float32_t x, float32_t y, float32_t z, dwConstCameraModelHandle_t obj)
Checks if the angle of a ray with the camera&#39;s optical center is below the maximum possible angle of ...
DW_API_PUBLIC dwStatus dwCameraModel_ray2Pixel(float32_t *u, float32_t *v, float32_t x, float32_t y, float32_t z, dwConstCameraModelHandle_t obj)
Projects a 3D point in pixel coordinates to a 2D pixel position.
Configuration parameters for a calibrated OCam sphere camera.
Definition: Rig.h:128
#define DW_DEPRECATED(msg)
Definition: Exports.h:66
DW_API_PUBLIC dwStatus dwCameraModel_getInversePolynomial(float32_t *invPoly, size_t *size, dwCameraModelHandle_t obj)
Returns the inverse polynomial used for the inverse distortion model.
DW_API_PUBLIC dwStatus dwCameraModel_getImageSize(uint32_t *width, uint32_t *height, dwConstCameraModelHandle_t obj)
Gets the width and height of the calibrated camera, in pixels.
DW_API_PUBLIC dwStatus dwCameraModel_release(dwCameraModelHandle_t obj)
Releases the calibrated camera.
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:71
Defines a 3x3 matrix of floating point numbers.
Definition: Types.h:237
struct dwCameraModelObject const * dwConstCameraModelHandle_t
A pointer to the handle representing a const calibrated camera.
Definition: CameraModel.h:70
Defines a two-element unsigned-integer vector.
Definition: Types.h:312
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:79
NVIDIA DriveWorks API: Core Methods
DW_API_PUBLIC dwStatus dwCameraModel_initializeOCam(dwCameraModelHandle_t *obj, const dwOCamCameraConfig *config, dwContextHandle_t context)
Creates and initializes a calibrated omnidirectional camera.
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:248
Configuration parameters for a calibrated pinhole camera.
Definition: Rig.h:94
DW_API_PUBLIC dwStatus dwCameraModel_applyImageTransform(const dwMatrix3f *transform, dwVector2ui newSize, dwCameraModelHandle_t obj)
Sets a new origin for the image.
struct dwCameraModelObject * dwCameraModelHandle_t
A pointer to the handle representing a calibrated camera model.
Definition: CameraModel.h:66
#define DW_API_PUBLIC
Definition: Exports.h:54
DW_API_PUBLIC dwStatus dwCameraModel_initialize(dwCameraModelHandle_t *camera, uint32_t sensorId, dwConstRigHandle_t obj)
Creates a calibrated camera model polymorphically for a compatible sensor.
NVIDIA DriveWorks API: Core Exports