DriveWorks SDK Reference
5.4.5418 Release
For Test and Development only

Rig.h
Go to the documentation of this file.
1 //
3 // Notice
4 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
5 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
6 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
7 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
8 //
9 // NVIDIA CORPORATION & AFFILIATES assumes no responsibility for the consequences of use of such
10 // information or for any infringement of patents or other rights of third parties that may
11 // result from its use. No license is granted by implication or otherwise under any patent
12 // or patent rights of NVIDIA CORPORATION & AFFILIATES. No third party distribution is allowed unless
13 // expressly authorized by NVIDIA. Details are subject to change without notice.
14 // This code supersedes and replaces all information previously supplied.
15 // NVIDIA CORPORATION & AFFILIATES products are not authorized for use as critical
16 // components in life support devices or systems without express written approval of
17 // NVIDIA CORPORATION & AFFILIATES.
18 //
19 // SPDX-FileCopyrightText: Copyright (c) 2015-2022 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
20 // SPDX-License-Identifier: LicenseRef-NvidiaProprietary
21 //
22 // NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
23 // property and proprietary rights in and to this material, related
24 // documentation and any modifications thereto. Any use, reproduction,
25 // disclosure or distribution of this material and related documentation
26 // without an express license agreement from NVIDIA CORPORATION or
27 // its affiliates is 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 6U
156 
162 typedef struct dwFThetaCameraConfig
163 {
165  uint32_t width;
166 
168  uint32_t height;
169 
172 
175 
179 
195 
201 
302 {
304  uint32_t width;
305 
307  uint32_t height;
308 
314 
317 
320 
325 
330 
335 
339 
341  dwFThetaCameraPolynomialType polynomialType;
343 
348 {
350  uint32_t width;
351 
353  uint32_t height;
354 
357 
360 
364 
383 dwStatus dwRig_initializeFromFile(dwRigHandle_t* const obj,
384  dwContextHandle_t const ctx,
385  char8_t const* const configurationFile);
386 
400 dwStatus dwRig_initializeFromString(dwRigHandle_t* const obj,
401  dwContextHandle_t const ctx,
402  char8_t const* const configurationString,
403  char8_t const* const relativeBasePath);
404 
414 dwStatus dwRig_reset(dwRigHandle_t const obj);
415 
426 dwStatus dwRig_release(dwRigHandle_t const obj);
427 
440 dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
441 
452 dwStatus dwRig_getGenericVehicle(dwGenericVehicle* const vehicle, dwConstRigHandle_t const obj);
453 
465 dwStatus dwRig_setVehicle(dwVehicle const* const vehicle, dwRigHandle_t const obj);
466 
477 dwStatus dwRig_setGenericVehicle(dwGenericVehicle const* const vehicle, dwRigHandle_t const obj);
478 
489 dwStatus dwRig_getVehicleIOConfigCount(uint32_t* const vioConfigCount,
490  dwConstRigHandle_t const obj);
491 
503 dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
504  dwConstRigHandle_t const obj);
505 
518 dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
519  dwSensorType const sensorType,
520  dwConstRigHandle_t const obj);
521 
538 dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
539  uint32_t const sensorId,
540  dwConstRigHandle_t const obj);
541 
556 DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
557  uint32_t const sensorId,
558  dwConstRigHandle_t const obj);
559 
574 DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
575  uint32_t const sensorId,
576  dwRigHandle_t const obj);
577 
597  uint32_t const sensorId,
598  dwConstRigHandle_t const obj);
599 
618  uint32_t const sensorId,
619  dwConstRigHandle_t const obj);
620 
638  uint32_t const sensorId,
639  dwConstRigHandle_t const obj);
640 
656  uint32_t const sensorId,
657  dwConstRigHandle_t const obj);
658 
674  uint32_t const sensorIdFrom,
675  uint32_t const sensorIdTo,
676  dwConstRigHandle_t const obj);
677 
694  uint32_t const sensorIdFrom,
695  uint32_t const sensorIdTo,
696  dwConstRigHandle_t const obj);
697 
714  uint32_t const sensorId,
715  dwRigHandle_t const obj);
716 
732 dwStatus dwRig_getSensorName(char8_t const** const sensorName,
733  uint32_t const sensorId,
734  dwConstRigHandle_t const obj);
735 
751 dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
752  uint32_t const sensorId,
753  dwConstRigHandle_t const obj);
754 
767 dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
768  uint32_t const sensorId,
769  dwConstRigHandle_t const obj);
770 
788 dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
789  char8_t const* const propertyName,
790  uint32_t const sensorId,
791  dwConstRigHandle_t const obj);
792 
808 dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
809  char8_t const* const propertyName,
810  uint32_t const sensorId,
811  dwRigHandle_t const obj);
828 dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
829  char8_t const* const propertyName,
830  dwConstRigHandle_t const obj);
831 
846 dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
847  char8_t const* const propertyName,
848  dwRigHandle_t const obj);
849 
864 dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
865  char8_t const* const sensorName,
866  dwConstRigHandle_t const obj);
881 dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t* const sensorId,
882  uint32_t const vehicleIOId,
883  dwConstRigHandle_t const obj);
884 
900 dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
901  dwSensorType const sensorType,
902  uint32_t const sensorTypeIndex,
903  dwConstRigHandle_t const obj);
904 
918 dwStatus dwRig_getSensorType(dwSensorType* const sensorType,
919  uint32_t const sensorId,
920  dwConstRigHandle_t const obj);
921 
937 dwStatus dwRig_getCameraModel(dwCameraModel* const cameraModel,
938  uint32_t const sensorId,
939  dwConstRigHandle_t const obj);
940 
956  uint32_t const sensorId,
957  dwConstRigHandle_t const obj);
958 
976 DW_DEPRECATED("OCam support will be removed from Driveworks in an upcmming release. Use FTheta instead.")
978  uint32_t const sensorId,
979  dwConstRigHandle_t const obj);
980 
1000  uint32_t const sensorId,
1001  dwConstRigHandle_t const obj);
1002 
1021  uint32_t const sensorId,
1022  dwConstRigHandle_t const obj);
1023 
1036  uint32_t const sensorId,
1037  dwRigHandle_t const obj);
1038 
1050 DW_DEPRECATED("OCam support will be removed from Driveworks in an upcoming release. Use FTheta instead.")
1052  uint32_t const sensorId,
1053  dwRigHandle_t const obj);
1054 
1068  uint32_t const sensorId,
1069  dwRigHandle_t const obj);
1070 
1083  uint32_t const sensorId,
1084  dwRigHandle_t const obj);
1085 
1105 dwStatus dwRig_serializeToFile(char8_t const* const configurationFile,
1106  dwConstRigHandle_t const obj);
1107 
1108 #ifdef __cplusplus
1109 }
1110 #endif
1111 
1113 #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
dwFThetaCameraPolynomialType polynomialType
Defines whether the polynomial parameter is the forward or backward polynomial.
Definition: Rig.h:341
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:356
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:301
float32_t e
Linear pixel transformation coefficient e (bottom left element) If all c, d and e are set to 0...
Definition: Rig.h:334
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
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:304
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...
Forward polynomial type, mapping angles (angle between ray and forward direction) to pixel distances ...
Definition: Rig.h:199
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:149
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:134
float32_t c
Affine matrix coefficient C.
Definition: Rig.h:143
dwFThetaCameraPolynomialType
Type of polynomial stored in FTheta.
Definition: Rig.h:190
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.
DEPRECATED: Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:162
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:262
DW_API_PUBLIC dwStatus dwRig_setGenericVehicle(dwGenericVehicle const *const vehicle, dwRigHandle_t const obj)
Sets the properties of a generic vehicle (car or truck).
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:319
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
Principal point coordinates: indicating the horizontal / vertical image coordinates of the principal ...
Definition: Rig.h:316
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:171
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:168
Specifies a 3D rigid transformation.
Definition: Types.h:467
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.
float32_t d
Linear pixel transformation coefficient d (top right element) If all c, d and e are set to 0...
Definition: Rig.h:329
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:359
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:174
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:362
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:353
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
Backward polynomial type, mapping pixel distances (offset from principal point) to angles (angle betw...
Definition: Rig.h:194
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:347
float32_t c
Linear pixel transformation matrix coefficient c (top left element) If all c, d and e are set to 0...
Definition: Rig.h:324
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.
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:307
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_getFThetaCameraConfigNew(dwFThetaCameraConfigNew *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the FTheta camera model.
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:165
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:350
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.
DW_API_PUBLIC dwStatus dwRig_setFThetaCameraConfigNew(dwFThetaCameraConfigNew const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the FTheta camera model.
struct dwRigObject * dwRigHandle_t
Handle representing the Rig interface.
Definition: Rig.h:70
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:315
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