DriveWorks SDK Reference
4.0.0 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-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 
46 #ifndef DW_RIG_RIG_H_
47 #define DW_RIG_RIG_H_
48 
49 #include <dw/core/Config.h>
50 #include <dw/core/base/Exports.h>
52 #include <dw/core/base/Types.h>
53 #include <dw/sensors/Sensors.h>
54 #include <dw/rig/Vehicle.h>
55 #include <stdint.h>
56 
57 #ifdef __cplusplus
58 extern "C" {
59 #endif
60 
69 typedef struct dwRigObject* dwRigHandle_t;
71 typedef struct dwRigObject const* dwConstRigHandle_t;
72 
74 // Calibrated cameras
75 
77 #define DW_MAX_RIG_CAMERA_COUNT 255U
78 
83 typedef enum dwCameraModel {
88 
89 #define DW_PINHOLE_DISTORTION_LENGTH 3U
90 
94 typedef struct dwPinholeCameraConfig
95 {
97  uint32_t width;
98 
100  uint32_t height;
101 
104 
107 
110 
113 
120 
121 #define DW_OCAM_POLY_LENGTH 5U
122 
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 
227 typedef struct dwFThetaCameraConfig
228 {
230  uint32_t width;
231 
233  uint32_t height;
234 
237 
240 
244 
249 {
251  uint32_t width;
252 
254  uint32_t height;
255 
258 
261 
265 
284 dwStatus dwRig_initializeFromFile(dwRigHandle_t* const obj,
285  dwContextHandle_t const ctx,
286  char8_t const* const configurationFile);
287 
301 dwStatus dwRig_initializeFromString(dwRigHandle_t* const obj,
302  dwContextHandle_t const ctx,
303  char8_t const* const configurationString,
304  char8_t const* const relativeBasePath);
305 
315 dwStatus dwRig_reset(dwRigHandle_t const obj);
316 
327 dwStatus dwRig_release(dwRigHandle_t const obj);
328 
341 dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
342 
353 dwStatus dwRig_getGenericVehicle(dwGenericVehicle* const vehicle, dwConstRigHandle_t const obj);
354 
366 dwStatus dwRig_setVehicle(dwVehicle const* const vehicle, dwRigHandle_t const obj);
367 
378 dwStatus dwRig_setGenericVehicle(dwGenericVehicle const* const vehicle, dwRigHandle_t const obj);
379 
390 dwStatus dwRig_getVehicleIOConfigCount(uint32_t* const vioConfigCount,
391  dwConstRigHandle_t const obj);
392 
404 dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
405  dwConstRigHandle_t const obj);
406 
419 dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
420  dwSensorType const sensorType,
421  dwConstRigHandle_t const obj);
422 
439 dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
440  uint32_t const sensorId,
441  dwConstRigHandle_t const obj);
442 
457 DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
458  uint32_t const sensorId,
459  dwConstRigHandle_t const obj);
460 
475 DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
476  uint32_t const sensorId,
477  dwRigHandle_t const obj);
478 
498  uint32_t const sensorId,
499  dwConstRigHandle_t const obj);
500 
519  uint32_t const sensorId,
520  dwConstRigHandle_t const obj);
521 
539  uint32_t const sensorId,
540  dwConstRigHandle_t const obj);
541 
557  uint32_t const sensorId,
558  dwConstRigHandle_t const obj);
559 
575  uint32_t const sensorIdFrom,
576  uint32_t const sensorIdTo,
577  dwConstRigHandle_t const obj);
578 
595  uint32_t const sensorIdFrom,
596  uint32_t const sensorIdTo,
597  dwConstRigHandle_t const obj);
598 
615  uint32_t const sensorId,
616  dwRigHandle_t const obj);
617 
633 dwStatus dwRig_getSensorName(char8_t const** const sensorName,
634  uint32_t const sensorId,
635  dwConstRigHandle_t const obj);
636 
649 dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
650  uint32_t const sensorId,
651  dwConstRigHandle_t const obj);
652 
665 dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
666  uint32_t const sensorId,
667  dwConstRigHandle_t const obj);
668 
686 dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
687  char8_t const* const propertyName,
688  uint32_t const sensorId,
689  dwConstRigHandle_t const obj);
690 
706 dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
707  char8_t const* const propertyName,
708  uint32_t const sensorId,
709  dwRigHandle_t const obj);
726 dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
727  char8_t const* const propertyName,
728  dwConstRigHandle_t const obj);
729 
744 dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
745  char8_t const* const propertyName,
746  dwRigHandle_t const obj);
747 
762 dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
763  char8_t const* const sensorName,
764  dwConstRigHandle_t const obj);
779 dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t* const sensorId,
780  uint32_t const vehicleIOId,
781  dwConstRigHandle_t const obj);
782 
798 dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
799  dwSensorType const sensorType,
800  uint32_t const sensorTypeIndex,
801  dwConstRigHandle_t const obj);
802 
816 dwStatus dwRig_getSensorType(dwSensorType* const sensorType,
817  uint32_t const sensorId,
818  dwConstRigHandle_t const obj);
819 
835 dwStatus dwRig_getCameraModel(dwCameraModel* const cameraModel,
836  uint32_t const sensorId,
837  dwConstRigHandle_t const obj);
838 
854  uint32_t const sensorId,
855  dwConstRigHandle_t const obj);
856 
874 DW_DEPRECATED("OCam support will be removed from Driveworks in an upcmming release. Use FTheta instead.")
876  uint32_t const sensorId,
877  dwConstRigHandle_t const obj);
878 
897  uint32_t const sensorId,
898  dwConstRigHandle_t const obj);
899 
912  uint32_t const sensorId,
913  dwRigHandle_t const obj);
914 
926 DW_DEPRECATED("OCam support will be removed from Driveworks in an upcoming release. Use FTheta instead.")
928  uint32_t const sensorId,
929  dwRigHandle_t const obj);
930 
943  uint32_t const sensorId,
944  dwRigHandle_t const obj);
945 
965 dwStatus dwRig_serializeToFile(char8_t const* const configurationFile,
966  dwConstRigHandle_t const obj);
967 
968 #ifdef __cplusplus
969 }
970 #endif
971 
973 #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.
NVIDIA DriveWorks API: Core Types
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:257
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:148
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:227
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:112
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:100
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:236
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:118
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:233
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:180
NVIDIA DriveWorks API: Sensors
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:97
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.
#define DW_DEPRECATED(msg)
Definition: Exports.h:66
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:260
dwCameraModel
Specifies the supported optical camera models.
Definition: Rig.h:83
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:71
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:239
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:263
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:254
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:79
NVIDIA DriveWorks API: Core Methods
char char8_t
Definition: Types.h:72
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:103
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:109
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:248
Configuration parameters for a calibrated pinhole camera.
Definition: Rig.h:94
#define DW_OCAM_POLY_LENGTH
Definition: Rig.h:121
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.
#define DW_PINHOLE_DISTORTION_LENGTH
Definition: Rig.h:89
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:106
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:54
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:230
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:251
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 Rig interface.
Definition: Rig.h:70
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.
NVIDIA DriveWorks API: Core Exports