DriveWorks SDK Reference
3.0.4260 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 <stdint.h>
57 
58 #ifdef __cplusplus
59 extern "C" {
60 #endif
61 
178 typedef struct dwRigObject* dwRigHandle_t;
180 typedef struct dwRigObject const* dwConstRigHandle_t;
181 
183 // Calibrated cameras
184 
186 #define DW_MAX_RIG_CAMERA_COUNT 255U
187 
192 typedef enum dwCameraModel {
196 } dwCameraModel;
197 
198 #define DW_PINHOLE_DISTORTION_LENGTH 3U
199 #define DW_VEHICLE_STEER_MAP_POLY_DEGREE 5U
200 
204 typedef struct dwPinholeCameraConfig
205 {
207  uint32_t width;
208 
210  uint32_t height;
211 
214 
217 
220 
223 
230 
231 #define DW_OCAM_POLY_LENGTH 5U
232 
236 typedef struct dwOCamCameraConfig
237 {
239  uint32_t width;
240 
242  uint32_t height;
243 
246 
249 
252 
255 
258 
262 
263 #define DW_FTHETA_POLY_LENGTH 5U
264 
268 typedef struct dwFThetaCameraConfig
269 {
271  uint32_t width;
272 
274  uint32_t height;
275 
278 
281 
285 
290 {
292  uint32_t width;
293 
295  uint32_t height;
296 
299 
302 
306 
312 typedef enum {
317 
321 
322 #define DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE 15U
323 
327 typedef struct dwVehicleTorqueLUT
328 {
331 
334 
339 
342 
346 
348 typedef struct dwVehicle
349 {
388  float32_t steeringWheelToSteeringMap[DW_VEHICLE_STEER_MAP_POLY_DEGREE + 1U];
389  float32_t maxSteeringWheelAngle;
393 } dwVehicle;
397 
416 dwStatus dwRig_initializeFromFile(dwRigHandle_t* obj,
417  dwContextHandle_t ctx,
418  char8_t const* const configurationFile);
419 
433 dwStatus dwRig_initializeFromString(dwRigHandle_t* obj,
434  dwContextHandle_t ctx,
435  char8_t const* const configurationString,
436  char8_t const* const relativeBasePath);
437 
447 dwStatus dwRig_reset(dwRigHandle_t const obj);
448 
459 dwStatus dwRig_release(dwRigHandle_t const obj);
460 
472 dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
473 
484 dwStatus dwRig_setVehicle(dwVehicle const* vehicle, dwRigHandle_t const obj);
485 
496 dwStatus dwRig_getVehicleIOConfigCount(uint32_t* vioConfigCount,
497  dwConstRigHandle_t const obj);
498 
510 dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
511  dwConstRigHandle_t const obj);
512 
525 dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
526  dwSensorType const sensorType,
527  dwConstRigHandle_t const obj);
528 
545 dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
546  uint32_t const sensorId,
547  dwConstRigHandle_t const obj);
548 
563 DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
564  uint32_t const sensorId,
565  dwConstRigHandle_t const obj);
566 
581 DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
582  uint32_t const sensorId,
583  dwRigHandle_t const obj);
584 
604  uint32_t const sensorId,
605  dwRigHandle_t const obj);
606 
625  uint32_t const sensorId,
626  dwConstRigHandle_t const obj);
627 
645  uint32_t const sensorId,
646  dwConstRigHandle_t const obj);
647 
663  uint32_t const sensorId,
664  dwConstRigHandle_t const obj);
665 
681  uint32_t const sensorIdFrom,
682  uint32_t const sensorIdTo,
683  dwConstRigHandle_t const obj);
684 
701  uint32_t const sensorIdFrom,
702  uint32_t const sensorIdTo,
703  dwConstRigHandle_t const obj);
704 
721  uint32_t const sensorId,
722  dwRigHandle_t const obj);
723 
739 dwStatus dwRig_getSensorName(char8_t const** const sensorName,
740  uint32_t const sensorId,
741  dwConstRigHandle_t const obj);
742 
755 dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
756  uint32_t const sensorId,
757  dwConstRigHandle_t const obj);
758 
771 dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
772  uint32_t const sensorId,
773  dwConstRigHandle_t const obj);
774 
792 dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
793  char8_t const* const propertyName,
794  uint32_t const sensorId,
795  dwConstRigHandle_t const obj);
796 
812 dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
813  char8_t const* const propertyName,
814  uint32_t const sensorId,
815  dwRigHandle_t const obj);
832 dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
833  char8_t const* const propertyName,
834  dwConstRigHandle_t const obj);
835 
850 dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
851  char8_t const* const propertyName,
852  dwRigHandle_t const obj);
853 
868 dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
869  char8_t const* sensorName,
870  dwConstRigHandle_t const obj);
885 dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t* const sensorId,
886  uint32_t vehicleIOId,
887  dwConstRigHandle_t const obj);
888 
904 dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
905  dwSensorType const sensorType,
906  uint32_t sensorTypeIndex,
907  dwConstRigHandle_t const obj);
908 
923  uint32_t const sensorId,
924  dwConstRigHandle_t const obj);
925 
941 dwStatus dwRig_getCameraModel(dwCameraModel* const cameraModel,
942  uint32_t const sensorId,
943  dwConstRigHandle_t const obj);
944 
960  uint32_t const sensorId,
961  dwConstRigHandle_t const obj);
962 
981  uint32_t const sensorId,
982  dwConstRigHandle_t const obj);
983 
1002  uint32_t const sensorId,
1003  dwConstRigHandle_t const obj);
1004 
1017  uint32_t const sensorId,
1018  dwRigHandle_t const obj);
1019 
1032  uint32_t const sensorId,
1033  dwRigHandle_t const obj);
1034 
1047  uint32_t const sensorId,
1048  dwRigHandle_t const obj);
1049 
1069 dwStatus dwRig_serializeToFile(char8_t const* configurationFile,
1070  dwConstRigHandle_t const obj);
1071 
1072 #ifdef __cplusplus
1073 }
1074 #endif
1075 
1077 #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.
float32_t centerOfMassToFrontAxle
Definition: Rig.h:376
float32_t aeroHeight
Definition: Rig.h:378
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:298
NVIDIA DriveWorks API: Core Types
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:239
float float32_t
Specifies POD types.
Definition: Types.h:70
float32_t d
Affine matrix coefficient D.
Definition: Rig.h:254
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: Sensors.h:156
Defines a three-element floating-point vector.
Definition: Types.h:319
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:242
float32_t c
Affine matrix coefficient C.
Definition: Rig.h:251
DW_API_PUBLIC dwStatus dwRig_setVehicle(dwVehicle const *vehicle, dwRigHandle_t const obj)
Sets the properties of the vehicle.
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:268
float32_t wheelbase
Definition: Rig.h:354
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:222
dwVector3f inertia3D
Definition: Rig.h:363
DW_API_PUBLIC dwStatus dwRig_getSensorType(dwSensorType *sensorType, uint32_t const sensorId, dwConstRigHandle_t const obj)
Returns the type of sensor based upon the sensorID sent into the method.
float32_t effectiveMass
Definition: Rig.h:365
float32_t centerOfMassHeight
Definition: Rig.h:377
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:210
float32_t e
Affine matrix coefficient E.
Definition: Rig.h:257
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:277
NVIDIA DriveWorks API: Core Methods
float32_t bumperRear
Definition: Rig.h:357
float32_t frontCorneringStiffness
Definition: Rig.h:367
float32_t distortion[DW_PINHOLE_DISTORTION_LENGTH]
Distortion polynomial coefficients [k_1, k_2, k_3].
Definition: Rig.h:228
float32_t centerOfMassToRearAxle
Definition: Rig.h:369
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.
DW_API_PUBLIC dwStatus dwRig_getOCamCameraConfig(dwOCamCameraConfig *config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the OCam camera model.
uint32_t height
Width of the image (in pixels)
Definition: Rig.h:274
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_serializeToFile(char8_t 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.
float32_t frontalArea
Definition: Rig.h:375
float32_t frontSteeringOffset
front wheel steering offset [radians].
Definition: Rig.h:392
dwStatus
Status definition.
Definition: Status.h:166
NVIDIA DriveWorks API: Sensors
DW_API_PUBLIC dwStatus dwRig_getSensorParameterUpdatedPath(char8_t const **const sensorParameter, uint32_t const sensorId, dwRigHandle_t const obj)
Gets the parameter string for a sensor with any path described by file=,video=,timestamp= property mo...
float32_t length
Definition: Rig.h:351
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:207
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:245
Configuration parameters for a calibrated OCam sphere camera.
Definition: Rig.h:236
float32_t driveByWireTimeConstant
Definition: Rig.h:372
DW_API_PUBLIC dwStatus dwRig_setSensorToRigTransformation(dwTransformation3f const *transformation, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the sensor to rig transformation for a sensor.
float32_t driveByWireTimeDelay
Definition: Rig.h:371
DW_API_PUBLIC dwStatus dwRig_findSensorByName(uint32_t *const sensorId, char8_t const *sensorName, dwConstRigHandle_t const obj)
Finds the sensor with the given name and returns its index.
float32_t maxEnginePower
Definition: Rig.h:380
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 rollingResistanceCoeff
Definition: Rig.h:379
DW_API_PUBLIC dwStatus dwRig_getPinholeCameraConfig(dwPinholeCameraConfig *config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the Pinhole camera model.
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:301
float32_t axlebaseFront
Definition: Rig.h:355
dwCameraModel
Specifies the supported optical camera models.
Definition: Rig.h:192
struct dwRigObject const * dwConstRigHandle_t
Definition: Rig.h:180
#define DW_VEHICLE_THROTTLE_BRAKE_LUT_SIZE
Definition: Rig.h:322
DW_API_PUBLIC dwStatus dwRig_initializeFromFile(dwRigHandle_t *obj, dwContextHandle_t ctx, char8_t const *const configurationFile)
Initializes the Rig Configuration module from a file.
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:280
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:263
float32_t bumperFront
Definition: Rig.h:358
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_setPinholeCameraConfig(dwPinholeCameraConfig const *config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the pinhole camera model.
float32_t hFOV
Horizontal FOV in radians.
Definition: Rig.h:304
DW_API_PUBLIC dwStatus dwRig_setFThetaCameraConfig(dwFThetaCameraConfig const *config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the FTheta camera model.
DW_API_PUBLIC dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t *const sensorId, uint32_t vehicleIOId, dwConstRigHandle_t const obj)
Finds a sensor with the given vehicleIO ID and returns the index.
dwVehicleWheels
Define index for each of the wheels on a 4 wheel vehicle.
Definition: Rig.h:312
#define DW_VEHICLE_STEER_MAP_POLY_DEGREE
Definition: Rig.h:199
uint32_t height
height of the image (in pixels)
Definition: Rig.h:295
Number of wheels describing the vehicle.
Definition: Rig.h:319
float32_t rearCorneringStiffness
Definition: Rig.h:368
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:80
DW_API_PUBLIC dwStatus dwRig_getVehicleIOConfigCount(uint32_t *vioConfigCount, dwConstRigHandle_t const obj)
Gets the number of vehicle IO sensors.
float32_t steeringCoefficient
Definition: Rig.h:359
float32_t widthWithMirrors
Definition: Rig.h:353
char char8_t
Definition: Types.h:72
float32_t mass
Definition: Rig.h:361
float32_t u0
U coordinate for the principal point (in pixels)
Definition: Rig.h:213
float32_t height
Definition: Rig.h:350
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_getVehicle(dwVehicle const **const vehicle, dwConstRigHandle_t const obj)
Gets the properties of the vehicle.
float32_t aerodynamicDragCoeff
Definition: Rig.h:374
float32_t focalX
Focal length in the X axis.
Definition: Rig.h:219
Configuration parameters for a calibrated FTheta camera.
Definition: Rig.h:289
Configuration parameters for a calibrated pinhole camera.
Definition: Rig.h:204
#define DW_OCAM_POLY_LENGTH
Definition: Rig.h:231
NVIDIA DriveWorks API: Core Exports
#define DW_PINHOLE_DISTORTION_LENGTH
Definition: Rig.h:198
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:216
DW_API_PUBLIC dwStatus dwRig_findSensorByTypeIndex(uint32_t *const sensorId, dwSensorType const sensorType, uint32_t sensorTypeIndex, dwConstRigHandle_t const obj)
Finds the absolute sensor index of the Nth sensor of a given type.
float32_t v0
V coordinate for the principal point (in pixels)
Definition: Rig.h:248
dwVehicleTorqueLUT torqueLUT
Definition: Rig.h:384
DW_API_PUBLIC dwStatus dwRig_setOCamCameraConfig(dwOCamCameraConfig const *config, uint32_t const sensorId, dwRigHandle_t const obj)
Sets the parameters of the OCam camera model.
Throttle and brake state (input) to longitudinal force (output) lookup tables.
Definition: Rig.h:327
float32_t axlebaseRear
Definition: Rig.h:356
float32_t width
Definition: Rig.h:352
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
DW_API_PUBLIC dwStatus dwRig_initializeFromString(dwRigHandle_t *obj, dwContextHandle_t ctx, char8_t const *const configurationString, char8_t const *const relativeBasePath)
Initializes the Rig Configuration module from a string.
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:271
float32_t brakeActuatorTimeConstant
Definition: Rig.h:382
float32_t throttleActuatorTimeConstant
Definition: Rig.h:381
uint32_t width
Width of the image (in pixels)
Definition: Rig.h:292
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:179
Properties of the vehicle.
Definition: Rig.h:348
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.