NVIDIA DriveOS Linux NSR SDK API Reference

7.0.3.0 Release
Rig.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: Copyright (c) 2015-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3  * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
4  *
5  * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
6  * property and proprietary rights in and to this material, related
7  * documentation and any modifications thereto. Any use, reproduction,
8  * disclosure or distribution of this material and related documentation
9  * without an express license agreement from NVIDIA CORPORATION or
10  * its affiliates is strictly prohibited.
11  */
12 
29 #ifndef DW_RIG_RIG_H_
30 #define DW_RIG_RIG_H_
31 
32 #include <dw/rig/RigTypes.h>
33 #include <dw/rig/Vehicle.h>
34 
35 #include <dw/core/base/Config.h>
36 #include <dw/core/base/Exports.h>
37 #include <dw/core/context/Context.h>
38 #include <dw/core/base/Types.h>
39 #include <dw/sensors/common/SensorTypes.h>
40 
41 #include <stdint.h>
42 
43 #ifdef __cplusplus
44 extern "C" {
45 #endif
46 
55 typedef struct dwRigObject* dwRigHandle_t;
58 typedef struct dwRigObject const* dwConstRigHandle_t;
59 
85  dwContextHandle_t const ctx,
86  char8_t const* const configurationFile);
87 
111  dwContextHandle_t const ctx,
112  char8_t const* const configurationString,
113  char8_t const* const relativeBasePath);
114 
130 
146 
166 dwStatus dwRig_getVehicle(dwVehicle const** const vehicle, dwConstRigHandle_t const obj);
167 
186 
205 dwStatus dwRig_setVehicle(dwVehicle const* const vehicle, dwRigHandle_t const obj);
206 
225 
242 dwStatus dwRig_getVehicleIOConfigCount(uint32_t* const vioConfigCount,
243  dwConstRigHandle_t const obj);
244 
260 dwStatus dwRig_getSensorCount(uint32_t* const sensorCount,
261  dwConstRigHandle_t const obj);
262 
279 dwStatus dwRig_getSensorCountOfType(uint32_t* const sensorCount,
280  dwSensorType const sensorType,
281  dwConstRigHandle_t const obj);
282 
302 dwStatus dwRig_getSensorProtocol(char8_t const** const sensorProtocol,
303  uint32_t const sensorId,
304  dwConstRigHandle_t const obj);
305 
323 DW_API_PUBLIC dwStatus dwRig_getSensorParameter(char8_t const** const sensorParameter,
324  uint32_t const sensorId,
325  dwConstRigHandle_t const obj);
326 
344 DW_API_PUBLIC dwStatus dwRig_setSensorParameter(char8_t const* const sensorParameter,
345  uint32_t const sensorId,
346  dwRigHandle_t const obj);
347 
370  uint32_t const sensorId,
371  dwConstRigHandle_t const obj);
372 
394  uint32_t const sensorId,
395  dwConstRigHandle_t const obj);
396 
417  uint32_t const sensorId,
418  dwConstRigHandle_t const obj);
419 
441  uint32_t const sensorId,
442  dwConstRigHandle_t const obj);
443 
465  uint32_t const sensorIdFrom,
466  uint32_t const sensorIdTo,
467  dwConstRigHandle_t const obj);
468 
491  uint32_t const sensorIdFrom,
492  uint32_t const sensorIdTo,
493  dwConstRigHandle_t const obj);
494 
515  uint32_t const sensorId,
516  dwRigHandle_t const obj);
517 
536 dwStatus dwRig_getSensorName(char8_t const** const sensorName,
537  uint32_t const sensorId,
538  dwConstRigHandle_t const obj);
539 
559 dwStatus dwRig_getSensorDataPath(char8_t const** const dataPath,
560  uint32_t const sensorId,
561  dwConstRigHandle_t const obj);
562 
581 dwStatus dwRig_getCameraTimestampPath(char8_t const** const timestampPath,
582  uint32_t const sensorId,
583  dwConstRigHandle_t const obj);
584 
606 dwStatus dwRig_getSensorPropertyByName(char8_t const** const propertyValue,
607  char8_t const* const propertyName,
608  uint32_t const sensorId,
609  dwConstRigHandle_t const obj);
610 
630 dwStatus dwRig_addOrSetSensorPropertyByName(char8_t const* const propertyValue,
631  char8_t const* const propertyName,
632  uint32_t const sensorId,
633  dwRigHandle_t const obj);
654 dwStatus dwRig_getPropertyByName(char8_t const** const propertyValue,
655  char8_t const* const propertyName,
656  dwConstRigHandle_t const obj);
657 
676 dwStatus dwRig_addOrSetPropertyByName(char8_t const* const propertyValue,
677  char8_t const* const propertyName,
678  dwRigHandle_t const obj);
679 
698 dwStatus dwRig_findSensorByName(uint32_t* const sensorId,
699  char8_t const* const sensorName,
700  dwConstRigHandle_t const obj);
719 dwStatus dwRig_findSensorIdFromVehicleIOId(uint32_t* const sensorId,
720  uint32_t const vehicleIOId,
721  dwConstRigHandle_t const obj);
722 
742 dwStatus dwRig_findSensorByTypeIndex(uint32_t* const sensorId,
743  dwSensorType const sensorType,
744  uint32_t const sensorTypeIndex,
745  dwConstRigHandle_t const obj);
746 
764 dwStatus dwRig_getSensorType(dwSensorType* const sensorType,
765  uint32_t const sensorId,
766  dwConstRigHandle_t const obj);
767 
787 dwStatus dwRig_getCameraModel(dwCameraModel* const cameraModel,
788  uint32_t const sensorId,
789  dwConstRigHandle_t const obj);
790 
810  uint32_t const sensorId,
811  dwConstRigHandle_t const obj);
812 
835  uint32_t const sensorId,
836  dwConstRigHandle_t const obj);
837 
859 DW_DEPRECATED("dwRig_getFThetaCameraConfigNew is replaced by dwRig_getFThetaCameraConfig.")
861  uint32_t const sensorId,
862  dwConstRigHandle_t const obj);
863 
883  uint32_t const sensorId,
884  dwRigHandle_t const obj);
885 
905  uint32_t const sensorId,
906  dwRigHandle_t const obj);
907 
931 dwStatus dwRig_serializeToFile(char8_t const* const configurationFile,
932  dwConstRigHandle_t const obj);
933 
934 #ifdef __cplusplus
935 }
936 #endif
937 
939 #endif // DW_RIG_RIG_H_
dwRig_addOrSetPropertyByName
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.
dwRig_getCameraTimestampPath
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.
dwRig_getSensorProtocol
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.
dwRig_getCameraModel
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.
dwConstRigHandle_t
struct dwRigObject const * dwConstRigHandle_t
Handle representing the const Rig interface.
Definition: Rig.h:58
dwRig_getSensorType
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.
dwRig_setFThetaCameraConfig
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.
dwRig_setSensorToRigTransformation
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.
dwRig_getSensorName
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.
ctx
DW_API_PUBLIC dwPointCloudRangeImageCreatorParams const *const const dwContextHandle_t ctx
Definition: PointCloudRangeImageCreator.h:293
dwRig_getFThetaCameraConfig
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.
dwRig_getSensorDataPath
DW_API_PUBLIC dwStatus dwRig_getSensorDataPath(char8_t const **const dataPath, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets path to sensor recording.
dwRig_initializeFromString
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.
dwRig_getGenericVehicle
DW_API_PUBLIC dwStatus dwRig_getGenericVehicle(dwGenericVehicle *const vehicle, dwConstRigHandle_t const obj)
Gets the properties of a generic vehicle (car or truck).
dwRig_getVehicle
DW_API_PUBLIC dwStatus dwRig_getVehicle(dwVehicle const **const vehicle, dwConstRigHandle_t const obj)
DEPRECATED: Gets the properties of a passenger car vehicle.
dwRig_getSensorParameter
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.
dwRig_getSensorCount
DW_API_PUBLIC dwStatus dwRig_getSensorCount(uint32_t *const sensorCount, dwConstRigHandle_t const obj)
Gets the number of all available sensors.
dwRig_getPinholeCameraConfig
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.
dwRig_reset
DW_API_PUBLIC dwStatus dwRig_reset(dwRigHandle_t const obj)
Resets the Rig Configuration module.
dwRig_setPinholeCameraConfig
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.
dwPinholeCameraConfig
Definition: RigTypes.h:126
dwFThetaCameraConfig
Configuration parameters for a calibrated FTheta camera.
Definition: RigTypes.h:307
dwRig_findSensorByName
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.
dwRig_getVehicleIOConfigCount
DW_API_PUBLIC dwStatus dwRig_getVehicleIOConfigCount(uint32_t *const vioConfigCount, dwConstRigHandle_t const obj)
Gets the number of vehicle IO sensors.
dwRig_getSensorToSensorTransformation
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.
char8_t
char char8_t
Definition: BasicTypes.h:47
dwVehicle
DEPRECATED: Properties of a passenger car vehicle.
Definition: Vehicle.h:472
dwRig_getNominalSensorToSensorTransformation
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_DEPRECATED
#define DW_DEPRECATED(msg)
Definition: Exports.h:50
dwRigHandle_t
struct dwRigObject * dwRigHandle_t
Handle representing the Rig interface.
Definition: Rig.h:56
dwSensorType
dwSensorType
Defines the type of sensors that are available in DriveWorks.
Definition: SensorTypes.h:74
dwRig_setSensorParameter
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.
dwRig_addOrSetSensorPropertyByName
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.
dwRig_getPropertyByName
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.
dwRig_initializeFromFile
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.
dwContextHandle_t
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:74
dwRig_getSensorCountOfType
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.
dwRig_getFThetaCameraConfigNew
DW_API_PUBLIC dwStatus dwRig_getFThetaCameraConfigNew(dwFThetaCameraConfig *const config, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the parameters of the FTheta camera model.
dwGenericVehicle
Vehicle description.
Definition: Vehicle.h:418
dwRig_findSensorIdFromVehicleIOId
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.
dwRig_serializeToFile
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.
dwRig_getSensorPropertyByName
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.
dwRig_getSensorToRigTransformation
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
dwStatus
Status definition.
Definition: ErrorDefs.h:27
dwRig_release
DW_API_PUBLIC dwStatus dwRig_release(dwRigHandle_t const obj)
Releases the Rig Configuration module.
dwTransformation3f
Specifies a 3D rigid transformation.
Definition: MatrixTypes.h:226
dwRig_getSensorFLUToRigTransformation
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.
dwRig_setGenericVehicle
DW_API_PUBLIC dwStatus dwRig_setGenericVehicle(dwGenericVehicle const *const vehicle, dwRigHandle_t const obj)
Sets the properties of a generic vehicle (car or truck).
dwRig_findSensorByTypeIndex
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
#define DW_API_PUBLIC
Definition: Exports.h:38
dwRig_setVehicle
DW_API_PUBLIC dwStatus dwRig_setVehicle(dwVehicle const *const vehicle, dwRigHandle_t const obj)
DEPRECATED: Sets the properties of a passenger car vehicle.
obj
const NvSciSyncObj *const obj
Definition: wfdext.h:120
dwRig_getSensorParameterUpdatedPath
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...
dwRig_getNominalSensorToRigTransformation
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.
dwCameraModel
dwCameraModel
Specifies the supported optical camera models.
Definition: RigTypes.h:54