DriveWorks SDK Reference
5.8.83 Release
For Test and Development only

Rig.h
Go to the documentation of this file.
1
2//
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/base/Config.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
58extern "C" {
59#endif
60
70typedef struct dwRigObject* dwRigHandle_t;
71typedef struct dwRigObject const* dwConstRigHandle_t;
72
74// Calibrated cameras
75
77#define DW_MAX_RIG_SENSOR_COUNT 128U
78
80#define DW_MAX_RIG_CAMERA_COUNT DW_MAX_RIG_SENSOR_COUNT
81
83#define DW_MAX_RIG_SENSOR_NAME_SIZE 64U
84
86#define DW_MAX_EXTRINSIC_PROFILE_NAME_SIZE 64U
87
89#define MAX_EXTRINSIC_PROFILE_COUNT 3U
90
95typedef enum dwCameraModel {
100
104#define DW_PINHOLE_DISTORTION_LENGTH 3U
105
132{
134 uint32_t width;
135
137 uint32_t height;
138
141
144
147
150
157
161#define DW_OCAM_POLY_LENGTH 5U
162
173typedef struct dwOCamCameraConfig
174{
176 uint32_t width;
177
179 uint32_t height;
180
183
186
189
192
195
199
203#define DW_FTHETA_POLY_LENGTH 6U
204
211{
213 uint32_t width;
214
216 uint32_t height;
217
220
223
227
245
253
349{
351 uint32_t width;
352
354 uint32_t height;
355
367
370
378
381
384
393
401
453{
455 uint32_t width;
456
458 uint32_t height;
459
462
465
469
491 dwContextHandle_t const ctx,
492 char8_t const* const configurationFile);
493
513 dwContextHandle_t const ctx,
514 char8_t const* const configurationString,
515 char8_t const* const relativeBasePath);
516
528
540
556dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
557
572
587dwStatus dwRig_setVehicle(dwVehicle const* const vehicle, dwRigHandle_t const obj);
588
603
616dwStatus dwRig_getVehicleIOConfigCount(uint32_t* const vioConfigCount,
617 dwConstRigHandle_t const obj);
618
630dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
631 dwConstRigHandle_t const obj);
632
645dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
646 dwSensorType const sensorType,
647 dwConstRigHandle_t const obj);
648
664dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
665 uint32_t const sensorId,
666 dwConstRigHandle_t const obj);
667
681DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
682 uint32_t const sensorId,
683 dwConstRigHandle_t const obj);
684
698DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
699 uint32_t const sensorId,
700 dwRigHandle_t const obj);
701
719DW_API_PUBLIC dwStatus dwRig_getSensorParameterUpdatedPath(char8_t const** const sensorParameter,
720 uint32_t const sensorId,
721 dwConstRigHandle_t const obj);
722
740 uint32_t const sensorId,
741 dwConstRigHandle_t const obj);
742
759 uint32_t const sensorId,
760 dwConstRigHandle_t const obj);
761
779 uint32_t const sensorId,
780 dwConstRigHandle_t const obj);
781
799 uint32_t const sensorIdFrom,
800 uint32_t const sensorIdTo,
801 dwConstRigHandle_t const obj);
802
821 uint32_t const sensorIdFrom,
822 uint32_t const sensorIdTo,
823 dwConstRigHandle_t const obj);
824
841 uint32_t const sensorId,
842 dwRigHandle_t const obj);
843
858dwStatus dwRig_getSensorName(char8_t const** const sensorName,
859 uint32_t const sensorId,
860 dwConstRigHandle_t const obj);
861
877dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
878 uint32_t const sensorId,
879 dwConstRigHandle_t const obj);
880
895dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
896 uint32_t const sensorId,
897 dwConstRigHandle_t const obj);
898
916dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
917 char8_t const* const propertyName,
918 uint32_t const sensorId,
919 dwConstRigHandle_t const obj);
920
936dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
937 char8_t const* const propertyName,
938 uint32_t const sensorId,
939 dwRigHandle_t const obj);
956dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
957 char8_t const* const propertyName,
958 dwConstRigHandle_t const obj);
959
974dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
975 char8_t const* const propertyName,
976 dwRigHandle_t const obj);
977
992dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
993 char8_t const* const sensorName,
994 dwConstRigHandle_t const obj);
1010 uint32_t const vehicleIOId,
1011 dwConstRigHandle_t const obj);
1012
1028dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
1029 dwSensorType const sensorType,
1030 uint32_t const sensorTypeIndex,
1031 dwConstRigHandle_t const obj);
1032
1047 uint32_t const sensorId,
1048 dwConstRigHandle_t const obj);
1049
1066 uint32_t const sensorId,
1067 dwConstRigHandle_t const obj);
1068
1084 uint32_t const sensorId,
1085 dwConstRigHandle_t const obj);
1086
1104DW_DEPRECATED("OCam support will be removed from Driveworks in an upcmming release. Use FTheta instead.")
1106 uint32_t const sensorId,
1107 dwConstRigHandle_t const obj);
1108
1128 uint32_t const sensorId,
1129 dwConstRigHandle_t const obj);
1130
1149 uint32_t const sensorId,
1150 dwConstRigHandle_t const obj);
1151
1167 uint32_t const sensorId,
1168 dwRigHandle_t const obj);
1169
1184DW_DEPRECATED("OCam support will be removed from Driveworks in an upcoming release. Use FTheta instead.")
1186 uint32_t const sensorId,
1187 dwRigHandle_t const obj);
1188
1205 uint32_t const sensorId,
1206 dwRigHandle_t const obj);
1207
1223 uint32_t const sensorId,
1224 dwRigHandle_t const obj);
1225
1245dwStatus dwRig_serializeToFile(char8_t const* const configurationFile,
1246 dwConstRigHandle_t const obj);
1247
1248#ifdef __cplusplus
1249}
1250#endif
1251
1253#endif // DW_RIG_RIG_H_
NVIDIA DriveWorks API: Sensors
NVIDIA DriveWorks API: Vehicle Parameters
NVIDIA DriveWorks API: Core Types
NVIDIA DriveWorks API: Core Methods
NVIDIA DriveWorks API: Core Exports
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:82
#define DW_DEPRECATED(msg)
Definition: Exports.h:66
#define DW_API_PUBLIC
Definition: Exports.h:54
dwStatus
Status definition.
Definition: Status.h:171
float float32_t
Specifies POD types.
Definition: Types.h:70
Specifies a 3D rigid transformation.
Definition: Types.h:536
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:213
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:140
float32_t focalY
Focal length in the Y axis (in pixels)
Definition: Rig.h:149
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:143
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:185
float32_t backwardsPoly[DW_FTHETA_POLY_LENGTH]
Pixel2ray backward projection polynomial coefficients.
Definition: Rig.h:225
dwFThetaCameraPolynomialType polynomialType
Defines whether the polynomial parameter either map angles to pixel-distances (called forward directi...
Definition: Rig.h:399
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:179
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:134
float32_t distortion[DW_PINHOLE_DISTORTION_LENGTH]
Polynomial coefficients [k_1, k_2, k_3] that allow to map undistored, normalized image coordinates (x...
Definition: Rig.h:155
float32_t focalX
Focal length in the X axis (in pixels)
Definition: Rig.h:146
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:461
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:182
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:222
float32_t poly[DW_OCAM_POLY_LENGTH]
Pixel2ray polynomial coefficients.
Definition: Rig.h:197
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:377
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:219
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:354
float32_t d
Linear pixel transformation coefficient d (top right element).
Definition: Rig.h:380
float32_t u0
Principal point coordinates: indicating the horizontal / vertical image coordinates of the principal ...
Definition: Rig.h:366
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:137
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:455
float32_t c
Affine matrix coefficient C.
Definition: Rig.h:188
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:216
float32_t e
Affine matrix coefficient E.
Definition: Rig.h:194
float32_t d
Affine matrix coefficient D.
Definition: Rig.h:191
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:464
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:351
float32_t e
Linear pixel transformation coefficient e (bottom left element).
Definition: Rig.h:383
float32_t polynomial[DW_FTHETA_POLY_LENGTH]
Polynomial describing either the mapping of angles to pixel-distances or the mapping of pixel-distanc...
Definition: Rig.h:392
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:369
float32_t hFOV
Horizontal FOV (in radians)
Definition: Rig.h:467
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:176
uint32_t height
Height of the image (in pixels)
Definition: Rig.h:458
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.
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_setVehicle(dwVehicle const *const vehicle, dwRigHandle_t const obj)
DEPRECATED: Sets the properties of a passenger car vehicle.
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.
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_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.
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_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_release(dwRigHandle_t const obj)
Releases the Rig Configuration module.
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.
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_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.
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.
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_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.
dwCameraModel
Specifies the supported optical camera models.
Definition: Rig.h:95
DW_API_PUBLIC dwStatus dwRig_reset(dwRigHandle_t const obj)
Resets the Rig Configuration module.
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_getGenericVehicle(dwGenericVehicle *const vehicle, dwConstRigHandle_t const obj)
Gets the properties of a generic vehicle (car or truck).
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
#define DW_FTHETA_POLY_LENGTH
Defines the number of distortion coefficients for the ftheta camera model.
Definition: Rig.h:203
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_serializeToFile(char8_t const *const configurationFile, dwConstRigHandle_t const obj)
This method serializes the rig-configuration object to a human-readable rig-configuration 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.
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.
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.
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_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_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_getVehicle(dwVehicle const **const vehicle, dwConstRigHandle_t const obj)
DEPRECATED: Gets the properties of a passenger car vehicle.
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.
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_getSensorCount(uint32_t *const sensorCount, dwConstRigHandle_t const obj)
Gets the number of all available sensors.
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.
#define DW_PINHOLE_DISTORTION_LENGTH
Defines the number of distortion coefficients for the pinhole camera model.
Definition: Rig.h:104
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...
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:71
dwFThetaCameraPolynomialType
Type of polynomial stored in FTheta.
Definition: Rig.h:238
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_setOCamCameraConfig(dwOCamCameraConfig const *const config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the OCam camera model.
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.
#define DW_OCAM_POLY_LENGTH
Defines the number of distortion coefficients for the OCAM camera model.
Definition: Rig.h:161
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.
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_getCameraModel(dwCameraModel *const cameraModel, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the model type of the camera intrinsics.
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_getVehicleIOConfigCount(uint32_t *const vioConfigCount, dwConstRigHandle_t const obj)
Gets the number of vehicle IO sensors.
DW_API_PUBLIC dwStatus dwRig_setGenericVehicle(dwGenericVehicle const *const vehicle, dwRigHandle_t const obj)
Sets the properties of a generic vehicle (car or truck).
@ DW_CAMERA_MODEL_FTHETA
Definition: Rig.h:98
@ DW_CAMERA_MODEL_PINHOLE
Definition: Rig.h:97
@ DW_CAMERA_MODEL_OCAM
Definition: Rig.h:96
@ DW_FTHETA_CAMERA_POLYNOMIAL_TYPE_PIXELDISTANCE_TO_ANGLE
Backward polynomial type, mapping pixel distances (offset from principal point) to angles (angle betw...
Definition: Rig.h:244
@ DW_FTHETA_CAMERA_POLYNOMIAL_TYPE_ANGLE_TO_PIXELDISTANCE
Forward polynomial type, mapping angles (angle between ray and forward direction) to pixel distances ...
Definition: Rig.h:251
DEPRECATED: Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:211
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:349
Vehicle description.
Definition: Vehicle.h:263
DEPRECATED: Configuration parameters for a calibrated ominidirectional (OCam) sphere camera.
Definition: Rig.h:174
Configuration parameters for a calibrated pinhole camera.
Definition: Rig.h:132
Configuration parameters for a calibrated stereographic camera.
Definition: Rig.h:453
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:316
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:188