DriveWorks SDK Reference
3.5.78 Release
For Test and Development only

Rig.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-2020 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 
48 #ifndef DW_RIG_RIG_H_
49 #define DW_RIG_RIG_H_
50 
51 #include <dw/core/Config.h>
52 #include <dw/core/Exports.h>
53 #include <dw/core/Context.h>
54 #include <dw/core/Types.h>
55 #include <dw/sensors/Sensors.h>
56 #include <dw/rig/Vehicle.h>
57 #include <stdint.h>
58 
59 #ifdef __cplusplus
60 extern "C" {
61 #endif
62 
71 typedef struct dwRigObject* dwRigHandle_t;
73 typedef struct dwRigObject const* dwConstRigHandle_t;
74 
76 // Calibrated cameras
77 
79 #define DW_MAX_RIG_CAMERA_COUNT 255U
80 
85 typedef enum dwCameraModel {
90 
91 #define DW_PINHOLE_DISTORTION_LENGTH 3U
92 
96 typedef struct dwPinholeCameraConfig
97 {
99  uint32_t width;
100 
102  uint32_t height;
103 
106 
109 
112 
115 
122 
123 #define DW_OCAM_POLY_LENGTH 5U
124 
128 typedef struct dwOCamCameraConfig
129 {
131  uint32_t width;
132 
134  uint32_t height;
135 
138 
141 
144 
147 
150 
154 
155 #define DW_FTHETA_POLY_LENGTH 5U
156 
160 typedef struct dwFThetaCameraConfig
161 {
163  uint32_t width;
164 
166  uint32_t height;
167 
170 
173 
177 
182 {
184  uint32_t width;
185 
187  uint32_t height;
188 
191 
194 
198 
217 dwStatus dwRig_initializeFromFile(dwRigHandle_t* const obj,
218  dwContextHandle_t const ctx,
219  char8_t const* const configurationFile);
220 
234 dwStatus dwRig_initializeFromString(dwRigHandle_t* const obj,
235  dwContextHandle_t const ctx,
236  char8_t const* const configurationString,
237  char8_t const* const relativeBasePath);
238 
248 dwStatus dwRig_reset(dwRigHandle_t const obj);
249 
260 dwStatus dwRig_release(dwRigHandle_t const obj);
261 
274 dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
275 
286 dwStatus dwRig_getGenericVehicle(dwGenericVehicle* const vehicle, dwConstRigHandle_t const obj);
287 
299 dwStatus dwRig_setVehicle(dwVehicle const* const vehicle, dwRigHandle_t const obj);
300 
311 dwStatus dwRig_setGenericVehicle(dwGenericVehicle const* const vehicle, dwRigHandle_t const obj);
312 
323 dwStatus dwRig_getVehicleIOConfigCount(uint32_t* const vioConfigCount,
324  dwConstRigHandle_t const obj);
325 
337 dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
338  dwConstRigHandle_t const obj);
339 
352 dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
353  dwSensorType const sensorType,
354  dwConstRigHandle_t const obj);
355 
372 dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
373  uint32_t const sensorId,
374  dwConstRigHandle_t const obj);
375 
390 DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
391  uint32_t const sensorId,
392  dwConstRigHandle_t const obj);
393 
408 DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
409  uint32_t const sensorId,
410  dwRigHandle_t const obj);
411 
431  uint32_t const sensorId,
432  dwConstRigHandle_t const obj);
433 
452  uint32_t const sensorId,
453  dwConstRigHandle_t const obj);
454 
472  uint32_t const sensorId,
473  dwConstRigHandle_t const obj);
474 
490  uint32_t const sensorId,
491  dwConstRigHandle_t const obj);
492 
508  uint32_t const sensorIdFrom,
509  uint32_t const sensorIdTo,
510  dwConstRigHandle_t const obj);
511 
528  uint32_t const sensorIdFrom,
529  uint32_t const sensorIdTo,
530  dwConstRigHandle_t const obj);
531 
548  uint32_t const sensorId,
549  dwRigHandle_t const obj);
550 
566 dwStatus dwRig_getSensorName(char8_t const** const sensorName,
567  uint32_t const sensorId,
568  dwConstRigHandle_t const obj);
569 
582 dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
583  uint32_t const sensorId,
584  dwConstRigHandle_t const obj);
585 
598 dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
599  uint32_t const sensorId,
600  dwConstRigHandle_t const obj);
601 
619 dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
620  char8_t const* const propertyName,
621  uint32_t const sensorId,
622  dwConstRigHandle_t const obj);
623 
639 dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
640  char8_t const* const propertyName,
641  uint32_t const sensorId,
642  dwRigHandle_t const obj);
659 dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
660  char8_t const* const propertyName,
661  dwConstRigHandle_t const obj);
662 
677 dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
678  char8_t const* const propertyName,
679  dwRigHandle_t const obj);
680 
695 dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
696  char8_t const* const sensorName,
697  dwConstRigHandle_t const obj);
712 dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t* const sensorId,
713  uint32_t const vehicleIOId,
714  dwConstRigHandle_t const obj);
715 
731 dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
732  dwSensorType const sensorType,
733  uint32_t const sensorTypeIndex,
734  dwConstRigHandle_t const obj);
735 
749 dwStatus dwRig_getSensorType(dwSensorType* const sensorType,
750  uint32_t const sensorId,
751  dwConstRigHandle_t const obj);
752 
768 dwStatus dwRig_getCameraModel(dwCameraModel* const cameraModel,
769  uint32_t const sensorId,
770  dwConstRigHandle_t const obj);
771 
787  uint32_t const sensorId,
788  dwConstRigHandle_t const obj);
789 
808  uint32_t const sensorId,
809  dwConstRigHandle_t const obj);
810 
829  uint32_t const sensorId,
830  dwConstRigHandle_t const obj);
831 
844  uint32_t const sensorId,
845  dwRigHandle_t const obj);
846 
859  uint32_t const sensorId,
860  dwRigHandle_t const obj);
861 
874  uint32_t const sensorId,
875  dwRigHandle_t const obj);
876 
896 dwStatus dwRig_serializeToFile(char8_t const* const configurationFile,
897  dwConstRigHandle_t const obj);
898 
899 #ifdef __cplusplus
900 }
901 #endif
902 
904 #endif // DW_RIG_RIG_H_
DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const *const sensorParameter, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameter string for a sensor.
DW_API_PUBLIC dwStatus dwRig_getVehicleIOConfigCount(uint32_t *const vioConfigCount, dwConstRigHandle_t const obj)
Gets the number of vehicle IO sensors.
DW_API_PUBLIC dwStatus dwRig_getOCamCameraConfig(dwOCamCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the OCam camera model.
DW_API_PUBLIC dwStatus dwRig_setOCamCameraConfig(dwOCamCameraConfig const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the OCam camera model.
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:190
NVIDIA DriveWorks API: Core Types
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:131
float float32_t
Specifies POD types.
Definition: Types.h:70
float32_t d
Affine matrix coefficient D.
Definition: Rig.h:146
DW_API_PUBLIC dwStatus dwRig_serializeToFile(char8_t const *const configurationFile, dwConstRigHandle_t const obj)
This method serializes the rig-configuration object to a human-readable rig-configuration file...
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:152
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:134
float32_t c
Affine matrix coefficient C.
Definition: Rig.h:143
DW_API_PUBLIC dwStatus dwRig_getSensorCountOfType(uint32_t *const sensorCount, dwSensorType const sensorType, dwConstRigHandle_t const obj)
Find number of sensors of a given type.
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:160
DW_API_PUBLIC dwStatus dwRig_initializeFromFile(dwRigHandle_t *const obj, dwContextHandle_t const ctx, char8_t const *const configurationFile)
Initializes the Rig Configuration module from a file.
DW_API_PUBLIC dwStatus dwRig_getSensorPropertyByName(char8_t const **const propertyValue, char8_t const *const propertyName, uint32_t const sensorId, dwConstRigHandle_t const obj)
Returns property stored inside of a sensor.
float32_t focalY
Focal length in the Y axis.
Definition: Rig.h:114
Vehicle description.
Definition: Vehicle.h:253
DW_API_PUBLIC dwStatus dwRig_setGenericVehicle(dwGenericVehicle const *const vehicle, dwRigHandle_t const obj)
Sets the properties of a generic vehicle (car or truck).
NVIDIA DriveWorks API: Vehicle Parameters
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:102
float32_t e
Affine matrix coefficient E.
Definition: Rig.h:149
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:169
NVIDIA DriveWorks API: Core Methods
DW_API_PUBLIC dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t *const sensorId, uint32_t const vehicleIOId, dwConstRigHandle_t const obj)
Finds a sensor with the given vehicleIO ID and returns the index.
float32_t distortion[DW_PINHOLE_DISTORTION_LENGTH]
Distortion polynomial coefficients [k_1, k_2, k_3].
Definition: Rig.h:120
DW_API_PUBLIC dwStatus dwRig_setVehicle(dwVehicle const *const vehicle, dwRigHandle_t const obj)
DEPRECATED: Sets the properties of a passenger car vehicle.
DW_API_PUBLIC dwStatus dwRig_release(dwRigHandle_t const obj)
Releases the Rig Configuration module.
DW_API_PUBLIC dwStatus dwRig_getSensorFLUToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the sensor FLU to rig transformation for a sensor.
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:166
Specifies a 3D rigid transformation.
Definition: Types.h:462
DW_API_PUBLIC dwStatus dwRig_getNominalSensorToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the nominal sensor to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRig_getSensorProtocol(char8_t const **const sensorProtocol, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the protocol string of a sensor.
DW_API_PUBLIC dwStatus dwRig_getCameraTimestampPath(char8_t const **const timestampPath, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets path to camera timestamp file.
DW_API_PUBLIC dwStatus dwRig_getSensorToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the sensor to rig transformation for a sensor.
dwStatus
Status definition.
Definition: Status.h:178
NVIDIA DriveWorks API: Sensors
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:99
DW_API_PUBLIC dwStatus dwRig_getSensorParameterUpdatedPath(char8_t const **const sensorParameter, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameter string for a sensor with any path described by file=,video=,timestamp= property mo...
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:137
Configuration parameters for a calibrated OCam sphere camera.
Definition: Rig.h:128
DW_API_PUBLIC dwStatus dwRig_findSensorByTypeIndex(uint32_t *const sensorId, dwSensorType const sensorType, uint32_t const sensorTypeIndex, dwConstRigHandle_t const obj)
Finds the absolute sensor index of the Nth sensor of a given type.
DW_API_PUBLIC dwStatus dwRig_getCameraModel(dwCameraModel *const cameraModel, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the model type of the camera intrinsics.
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:193
dwCameraModel
Specifies the supported optical camera models.
Definition: Rig.h:85
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:73
DW_API_PUBLIC dwStatus dwRig_setFThetaCameraConfig(dwFThetaCameraConfig const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the FTheta camera model.
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:172
DW_API_PUBLIC dwStatus dwRig_getSensorName(char8_t const **const sensorName, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the name of a sensor as given in the configuration.
#define DW_FTHETA_POLY_LENGTH
Definition: Rig.h:155
DW_API_PUBLIC dwStatus dwRig_addOrSetPropertyByName(char8_t const *const propertyValue, char8_t const *const propertyName, dwRigHandle_t const obj)
Overwrite content of an existing rig property.
DW_API_PUBLIC dwStatus dwRig_getSensorType(dwSensorType *const sensorType, uint32_t const sensorId, dwConstRigHandle_t const obj)
Returns the type of sensor based upon the sensorID sent into the method.
float32_t hFOV
Horizontal FOV in radians.
Definition: Rig.h:196
DW_API_PUBLIC dwStatus dwRig_getGenericVehicle(dwGenericVehicle *const vehicle, dwConstRigHandle_t const obj)
Gets the properties of a generic vehicle (car or truck).
DW_API_PUBLIC dwStatus dwRig_getPinholeCameraConfig(dwPinholeCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the Pinhole camera model.
uint32_t height
height of the image (in pixels)
Definition: Rig.h:187
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:80
char char8_t
Definition: Types.h:72
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:105
DW_API_PUBLIC dwStatus dwRig_getSensorDataPath(char8_t const **const dataPath, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets path to sensor recording.
DW_API_PUBLIC dwStatus dwRig_setSensorToRigTransformation(dwTransformation3f const *const transformation, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the sensor to rig transformation for a sensor.
DW_API_PUBLIC dwStatus dwRig_getVehicle(dwVehicle const **const vehicle, dwConstRigHandle_t const obj)
DEPRECATED: Gets the properties of a passenger car vehicle.
float32_t focalX
Focal length in the X axis.
Definition: Rig.h:111
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:181
Configuration parameters for a calibrated pinhole camera.
Definition: Rig.h:96
#define DW_OCAM_POLY_LENGTH
Definition: Rig.h:123
DW_API_PUBLIC dwStatus dwRig_findSensorByName(uint32_t *const sensorId, char8_t const *const sensorName, dwConstRigHandle_t const obj)
Finds the sensor with the given name and returns its index.
NVIDIA DriveWorks API: Core Exports
#define DW_PINHOLE_DISTORTION_LENGTH
Definition: Rig.h:91
DW_API_PUBLIC dwStatus dwRig_getSensorToSensorTransformation(dwTransformation3f *const transformation, uint32_t const sensorIdFrom, uint32_t const sensorIdTo, dwConstRigHandle_t const obj)
Gets the sensor to sensor transformation for a pair of sensors.
DW_API_PUBLIC dwStatus dwRig_getFThetaCameraConfig(dwFThetaCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the FTheta camera model.
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:108
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:140
DW_API_PUBLIC dwStatus dwRig_initializeFromString(dwRigHandle_t *const obj, dwContextHandle_t const ctx, char8_t const *const configurationString, char8_t const *const relativeBasePath)
Initializes the Rig Configuration module from a string.
DW_API_PUBLIC dwStatus dwRig_setPinholeCameraConfig(dwPinholeCameraConfig const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the pinhole camera model.
DW_API_PUBLIC dwStatus dwRig_reset(dwRigHandle_t const obj)
Resets the Rig Configuration module.
DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const **const sensorParameter, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameter string for a sensor.
DW_API_PUBLIC dwStatus dwRig_getSensorCount(uint32_t *const sensorCount, dwConstRigHandle_t const obj)
Gets the number of all available sensors.
#define DW_API_PUBLIC
Definition: Exports.h:56
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:163
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:184
DW_API_PUBLIC dwStatus dwRig_getNominalSensorToSensorTransformation(dwTransformation3f *const transformation, uint32_t const sensorIdFrom, uint32_t const sensorIdTo, dwConstRigHandle_t const obj)
Gets the nominal sensor to sensor transformation for a pair of sensors.
struct dwRigObject * dwRigHandle_t
Handle representing the Sensor Abstraction Layer interface.
Definition: Rig.h:72
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:306
DW_API_PUBLIC dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const *const propertyValue, char8_t const *const propertyName, uint32_t const sensorId, dwRigHandle_t const obj)
Overwrite content of an existing sensor property.
DW_API_PUBLIC dwStatus dwRig_getPropertyByName(char8_t const **const propertyValue, char8_t const *const propertyName, dwConstRigHandle_t const obj)
Returns property stored inside of rig.