77#define DW_MAX_RIG_SENSOR_COUNT 128U
80#define DW_MAX_RIG_CAMERA_COUNT DW_MAX_RIG_SENSOR_COUNT
83#define DW_MAX_RIG_SENSOR_NAME_SIZE 64U
86#define DW_MAX_EXTRINSIC_PROFILE_NAME_SIZE 64U
89#define MAX_EXTRINSIC_PROFILE_COUNT 3U
104#define DW_PINHOLE_DISTORTION_LENGTH 3U
161#define DW_OCAM_POLY_LENGTH 5U
203#define DW_FTHETA_POLY_LENGTH 6U
492 char8_t const*
const configurationFile);
514 char8_t const*
const configurationString,
515 char8_t const*
const relativeBasePath);
665 uint32_t
const sensorId,
682 uint32_t
const sensorId,
699 uint32_t
const sensorId,
720 uint32_t
const sensorId,
740 uint32_t
const sensorId,
759 uint32_t
const sensorId,
779 uint32_t
const sensorId,
799 uint32_t
const sensorIdFrom,
800 uint32_t
const sensorIdTo,
821 uint32_t
const sensorIdFrom,
822 uint32_t
const sensorIdTo,
841 uint32_t
const sensorId,
859 uint32_t
const sensorId,
878 uint32_t
const sensorId,
896 uint32_t
const sensorId,
917 char8_t const*
const propertyName,
918 uint32_t
const sensorId,
937 char8_t const*
const propertyName,
938 uint32_t
const sensorId,
957 char8_t const*
const propertyName,
975 char8_t const*
const propertyName,
993 char8_t const*
const sensorName,
1010 uint32_t
const vehicleIOId,
1030 uint32_t
const sensorTypeIndex,
1047 uint32_t
const sensorId,
1066 uint32_t
const sensorId,
1084 uint32_t
const sensorId,
1104DW_DEPRECATED(
"OCam support will be removed from Driveworks in an upcmming release. Use FTheta instead.")
1106 uint32_t const sensorId,
1128 uint32_t const sensorId,
1149 uint32_t const sensorId,
1167 uint32_t const sensorId,
1184DW_DEPRECATED("OCam support will be removed from Driveworks in an upcoming release. Use FTheta instead.")
1186 uint32_t const sensorId,
1205 uint32_t const sensorId,
1223 uint32_t const sensorId,
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.
#define DW_DEPRECATED(msg)
dwStatus
Status definition.
float float32_t
Specifies POD types.
uint32_t width
Width of the image (in pixels)
float32_t u0
U coordinate for the principal point (in pixels)
float32_t focalY
Focal length in the Y axis (in pixels)
float32_t v0
V coordinate for the principal point (in pixels)
float32_t v0
V coordinate for the principal point (in pixels)
float32_t backwardsPoly[DW_FTHETA_POLY_LENGTH]
Pixel2ray backward projection polynomial coefficients.
dwFThetaCameraPolynomialType polynomialType
Defines whether the polynomial parameter either map angles to pixel-distances (called forward directi...
uint32_t height
Height of the image (in pixels)
uint32_t width
Width of the image (in pixels)
float32_t distortion[DW_PINHOLE_DISTORTION_LENGTH]
Polynomial coefficients [k_1, k_2, k_3] that allow to map undistored, normalized image coordinates (x...
float32_t focalX
Focal length in the X axis (in pixels)
float32_t u0
U coordinate for the principal point (in pixels)
float32_t u0
U coordinate for the principal point (in pixels)
float32_t v0
V coordinate for the principal point (in pixels)
float32_t poly[DW_OCAM_POLY_LENGTH]
Pixel2ray polynomial coefficients.
float32_t c
Linear pixel transformation matrix coefficient c (top left element) If all c, d, and e are set to 0....
float32_t u0
U coordinate for the principal point (in pixels)
uint32_t height
Height of the image (in pixels)
float32_t d
Linear pixel transformation coefficient d (top right element).
float32_t u0
Principal point coordinates: indicating the horizontal / vertical image coordinates of the principal ...
uint32_t height
Height of the image (in pixels)
uint32_t width
Width of the image (in pixels)
float32_t c
Affine matrix coefficient C.
uint32_t height
Height of the image (in pixels)
float32_t e
Affine matrix coefficient E.
float32_t d
Affine matrix coefficient D.
float32_t v0
V coordinate for the principal point (in pixels)
uint32_t width
Width of the image (in pixels)
float32_t e
Linear pixel transformation coefficient e (bottom left element).
float32_t polynomial[DW_FTHETA_POLY_LENGTH]
Polynomial describing either the mapping of angles to pixel-distances or the mapping of pixel-distanc...
float32_t v0
V coordinate for the principal point (in pixels)
float32_t hFOV
Horizontal FOV (in radians)
uint32_t width
Width of the image (in pixels)
uint32_t height
Height of the image (in pixels)
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.
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.
#define DW_FTHETA_POLY_LENGTH
Defines the number of distortion coefficients for the ftheta camera model.
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.
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
dwFThetaCameraPolynomialType
Type of polynomial stored in FTheta.
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.
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_PINHOLE
@ DW_FTHETA_CAMERA_POLYNOMIAL_TYPE_PIXELDISTANCE_TO_ANGLE
Backward polynomial type, mapping pixel distances (offset from principal point) to angles (angle betw...
@ DW_FTHETA_CAMERA_POLYNOMIAL_TYPE_ANGLE_TO_PIXELDISTANCE
Forward polynomial type, mapping angles (angle between ray and forward direction) to pixel distances ...
DEPRECATED: Configuration parameters for a calibrated FTheta camera.
Configuration parameters for a calibrated FTheta camera.
DEPRECATED: Configuration parameters for a calibrated ominidirectional (OCam) sphere camera.
Configuration parameters for a calibrated pinhole camera.
Configuration parameters for a calibrated stereographic camera.
DEPRECATED: Properties of a passenger car vehicle.
dwSensorType
Defines the type of sensors that are available in DriveWorks.